Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

"no offboard signal" even though trajectory_setpoint and offboard_control_mode get published in uorb #22456

Open
NXPBenjaminK opened this issue Nov 29, 2023 · 5 comments
Assignees

Comments

@NXPBenjaminK
Copy link
Contributor

Describe the bug

Hi! I have written a node, which publishes velocity offboard-commands using the uxrce-dds-bridge.
The trajectory_setpoint and offboard_control_mode messages get transmitted and are visible in uorb (see below)
However when i try to switch to offboard mode, i get the following error (see sreenshot below): "Critical: Switching to mode 'Offboard' is currently not possible No offboard signal"

Arming the vehicle via uxrce_dds bridge while in offboard-mode and with skipping of the pre-flight checks causes the vehicle to immediatly go into failsafe with the same error.

Using the px4_ros_com offboard_control node causes the same problem.

The relevant part of my code:

VelocityController::VelocityController(void) : Node("px4_offboard_control") {
    controll_mode_msg.position = false;
    controll_mode_msg.velocity = true;
    pub_offboard_control_mode = this->create_publisher<px4_msgs::msg::OffboardControlMode>("/fmu/in/offboard_control_mode", 10);
    pub_trajectory_setpoint = this->create_publisher<px4_msgs::msg::TrajectorySetpoint>("/fmu/in/trajectory_setpoint", 10);
    ...
}
...
void VelocityController::publish_trajectory_setpoint(void){
    publish_offboard_control_mode();
    timestamp = this->get_clock()->now().nanoseconds() / 1000;
    publish(trajectory_msg);
}
...
void VelocityController::publish_offboard_control_mode()
{
    controll_mode_msg.timestamp = this->get_clock()->now().nanoseconds() / 1000;
    pub_offboard_control_mode->publish(controll_mode_msg);
}

To Reproduce

  • Turn on Rover
  • On Companion: start uxrce-dds-bridge
  • On Companion start either px4_ros_com offboard_control or px4_offboard_control velocity_controller
  • Disengage kill switch
  • Arm Rover
  • Switch to Offboard mode

Expected behavior

Rover should slowly drive West

Screenshot / Media

screen
uorb_msgs
qgc output

Flight Log

https://logs.px4.io/plot_app?log=3c4983fe-dae7-4ba4-b823-88a2fa28ce32

Software Version

6a34b63

HW arch: NXP_MR_CANHUBK3
HW type: MR-CANHUBK3-ADAP
HW version: 0x000
HW revision: 0x000
PX4 git-hash: 6a34b63
PX4 version: 1.15.0 0 (17760256)
PX4 git-branch: main
OS: NuttX
OS version: Release 11.0.0 (184549631)
OS git-hash: e7da5ac0e660238cb353948b2a9118579727267a
Build datetime: Nov 28 2023 16:44:37
Build uri: localhost
Build variant: fmu
Toolchain: GNU GCC, 9.3.1 20200408 (release)
PX4GUID: 00086702193221071965ffffffffffffffff
MCU: S32K344, rev. 0

Flight controller

NXP_MR_CANHUBK3

Vehicle type

Rover

How are the different components wired up (including port information)

No response

Additional context

No response

@dagar dagar self-assigned this Nov 29, 2023
@DronecodeBot
Copy link

This issue has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-community-q-a-november-29-2023/35461/1

@NXPBenjaminK
Copy link
Contributor Author

NXPBenjaminK commented Dec 1, 2023

I have now teted it on a drone with an px4_fmu6xrt controller and have the same issue there.
Also when trying the example from the new dynamic mode system it works for ~3 seconds and then the fmu crashes completly and needs to be power cycled (on both the rover and the drone).

This is the output over the serial consol when trying the dynamic mode:

WARN [health_and_arming_checks] No response from 0, flagging unresponsive
WARN [failsafe] Failsafe activated
INFO [commander] Disarmed by auto preflight disarming
INFO [logger] closed logfile, bytes written: 412989
INFO [commander] Connection to ground station lost

Here is a flight log of the dynamic mode test on a drone:
https://review.px4.io/plot_app?log=d631e501-5910-41fc-ba1e-36deab1da9cc

@dk7xe
Copy link
Contributor

dk7xe commented Dec 1, 2023

important to get that solved cause we like to test UWB based indoor localization and navigation from ROS2.
@bkueng

@NXPBenjaminK
Copy link
Contributor Author

I found the issue:
We are running these vehicles indoors without a gps signal and apparently for velocity control there is still gps needed.
I tested it with attitude control and it now works (the "old" offboard mode).

@hamishwillee maybe this could be a little clearer in the px4 docu

@beniaminopozzan
Copy link
Member

Hi @NXPBenjaminK , I'm glad that you found the root of the issue.

Yeah, looking into it the error message is quite unclear

if (reporter.failsafeFlags().offboard_control_signal_lost && reporter.failsafeFlags().mode_req_offboard_signal != 0) {
/* EVENT
* @description
* The offboard component is not sending setpoints or the required estimate (e.g. position) is missing.
*/
reporter.armingCheckFailure((NavModes)reporter.failsafeFlags().mode_req_offboard_signal, health_component_t::system,
events::ID("check_modes_offboard_signal"),
events::Log::Error, "No offboard signal");
reporter.clearCanRunBits((NavModes)reporter.failsafeFlags().mode_req_offboard_signal);
}

as it combines the condition "no stepoint" and "no valid required estimate". Thank you for raising this.

Regarding the need of gps:

void OffboardChecks::checkAndReport(const Context &context, Report &reporter)
{
reporter.failsafeFlags().offboard_control_signal_lost = true;
offboard_control_mode_s offboard_control_mode;
if (_offboard_control_mode_sub.copy(&offboard_control_mode)) {
bool data_is_recent = hrt_absolute_time() < offboard_control_mode.timestamp
+ static_cast<hrt_abstime>(_param_com_of_loss_t.get() * 1_s);
bool offboard_available = (offboard_control_mode.position || offboard_control_mode.velocity
|| offboard_control_mode.acceleration || offboard_control_mode.attitude || offboard_control_mode.body_rate
|| offboard_control_mode.thrust_and_torque || offboard_control_mode.direct_actuator) && data_is_recent;
if (offboard_control_mode.position && reporter.failsafeFlags().local_position_invalid) {
offboard_available = false;
} else if (offboard_control_mode.velocity && reporter.failsafeFlags().local_velocity_invalid) {
offboard_available = false;
} else if (offboard_control_mode.acceleration && reporter.failsafeFlags().local_velocity_invalid) {
// OFFBOARD acceleration handled by position controller
offboard_available = false;
}
// This is a mode requirement, no need to report
reporter.failsafeFlags().offboard_control_signal_lost = !offboard_available;
}
}

if you only have the velocity flag set, then you need a valid velocity estimate. I does not need to come from a GPS.

Finally, the documentation https://docs.px4.io/main/en/flight_modes/offboard.html#ros-2-messages says that velocity is needed :)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: No status
Development

No branches or pull requests

5 participants