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

Obstacle Avoidance prearm checks and log health status #11638

Merged
merged 10 commits into from
Mar 27, 2019
2 changes: 1 addition & 1 deletion src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3967,7 +3967,7 @@ void Commander::data_link_check(bool &status_changed)

//if avoidance never started
if (_datalink_last_heartbeat_avoidance_system == 0
&& hrt_elapsed_time(&_datalink_last_heartbeat_avoidance_system) > _onboard_boot_timeout.get() * 1_s) {
&& hrt_elapsed_time(&_datalink_last_heartbeat_avoidance_system) > _oa_boot_timeout.get() * 1_s) {
if (!print_msg_once) {
mavlink_log_critical(&mavlink_log_pub, "Avoidance system not available!");
print_msg_once = true;
Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
(ParamFloat<px4::params::COM_DISARM_LAND>) _disarm_when_landed_timeout,

(ParamInt<px4::params::COM_OBS_AVOID>) _obs_avoid,
(ParamInt<px4::params::COM_ONB_BOOT_T>) _onboard_boot_timeout
(ParamInt<px4::params::COM_OA_BOOT_T>) _oa_boot_timeout

)

Expand Down
12 changes: 6 additions & 6 deletions src/modules/commander/commander_params.c
Original file line number Diff line number Diff line change
Expand Up @@ -798,22 +798,22 @@ PARAM_DEFINE_INT32(NAV_DLL_ACT, 0);
PARAM_DEFINE_INT32(NAV_RCL_ACT, 2);

/**
* Flag to enable obstacle avoidance
* Flag to enable obstacle avoidance.
*
* @boolean
* @group Mission
*/
PARAM_DEFINE_INT32(COM_OBS_AVOID, 0);

/**
* Set onboard controller bootup timeout
* Set avoidance system bootup timeout.
*
* This parameter defines the bootup timeout.
* After the timeout, a mavlink message that tells the user that the avoidance system
* is not available is sent.
* The avoidance system running on the companion computer is expected to boot
* within this time and start providing trajectory points.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is this true? Is it about trajectory points being sent? Or is it about a heartbeat?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, it is true. In the actual implementation, as soon as the avoidance node is running sends both heartbeats and trajectory points. On the long term, this behavior will probably be changed.

If we want to maintain a more general statement we could go for:
The avoidance system running on the companion computer is expected to boot within this time, after which its functionalities are fully operative.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No if it's true it's fine.

* If no avoidance system is detected a MAVLink warning message is sent.
* @group Commander
* @unit s
* @min 0
* @max 200
*/
PARAM_DEFINE_INT32(COM_ONB_BOOT_T, 100);
PARAM_DEFINE_INT32(COM_OA_BOOT_T, 100);