Hello everyone,
i want to change from Stabilize disarmed to Stabilize armed using MAVLINK.
I have to send a MAV_MODE message:
Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.
Field Name | Type | Description |
---|---|---|
target_system | uint8_t | The system setting the mode |
base_mode | uint8_t | The new base mode |
custom_mode | uint32_t | The new autopilot-specific mode. This field can be ignored by an autopilot. |
So, the base_mode would be 128 because is the value for MAV_MODE_FLAG_SAFETY_ARMED in the enum MAV_MODE_FLAG.
Now, i have to write a value for custom_mode but i don't know which value i should write. Can someone help me please?
Thanks!
Replies
Hello,
I have been trying to run PX4 code on SITL simulation. In qGroundControl I am not able to switch to some modes. For e.g Follow me. I am pretty new to all this. I am not sure where am I going wrong.
David Gitz said:
I don't know if you got anywhere with this, but here's part of the answer. I have been going through the ArduPlane code and found that a) it ignores the MAV_MODE_FLAG
case MAVLINK_MSG_ID_SET_MODE:
{
// decode
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
// custom_mode instead.
break;
}
switch (packet.custom_mode) {
case MANUAL:
case CIRCLE:
case STABILIZE:
case FLY_BY_WIRE_A:
case FLY_BY_WIRE_B:
case AUTO:
case RTL:
case LOITER:
set_mode((enum FlightMode)packet.custom_mode);
break;
}
b) it only listens to the Custom Flag, which is defined in defines.h:
enum FlightMode {
MANUAL = 0,
CIRCLE = 1,
STABILIZE = 2,
FLY_BY_WIRE_A = 5,
FLY_BY_WIRE_B = 6,
AUTO = 10,
RTL = 11,
LOITER = 12,
GUIDED = 15,
INITIALISING = 16
};
So it appears that you want to set your custom flag to 2 for Stabilize.
Did you ever get any insight into this?