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

mavros_msgs::Status.armed not properly set as boolean #990

Closed
ndepal opened this issue Apr 5, 2018 · 1 comment
Closed

mavros_msgs::Status.armed not properly set as boolean #990

ndepal opened this issue Apr 5, 2018 · 1 comment
Labels
Milestone

Comments

@ndepal
Copy link

ndepal commented Apr 5, 2018

The armed flag in mavros_msgs::Status is not properly written as a boolean true when the vehicle is armed. It is written to 128.

The reason for this is that booleans in ROS messages are really uint8s, so there is no implicit cast to bool in the below line, as was perhaps assumed.

state_msg->armed = hb.base_mode & enum_value(MAV_MODE_FLAG::SAFETY_ARMED);

The problem with this is that the following check does not work:

if (status.armed == true) {
    // will never get here
}

This is problematic as one would assume that this works since the documentation/the message definition claims that status.armed is a boolean.

The below works of course:

if (status.armed) {
    // will get here
}

Changing the above line to the following fixes the issue:

state_msg->armed = (bool)(hb.base_mode & enum_value(MAV_MODE_FLAG::SAFETY_ARMED));
@vooon vooon closed this as completed in ce4f76e Apr 5, 2018
@vooon vooon added this to the Version 0.24 milestone Apr 5, 2018
@vooon vooon added the fix label Apr 5, 2018
@ndepal
Copy link
Author

ndepal commented Apr 5, 2018

Thanks!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

2 participants