forked from Archive/PX4-Autopilot
commander: add VEHICLE_CMD_SET_NAV_STATE internal command
This commit is contained in:
parent
fbbccf6997
commit
889b6a1a78
|
@ -103,6 +103,7 @@ uint16 VEHICLE_CMD_DO_WINCH = 42600 # Command to operate winch.
|
||||||
# PX4 vehicle commands (beyond 16 bit mavlink commands)
|
# PX4 vehicle commands (beyond 16 bit mavlink commands)
|
||||||
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX)
|
uint32 VEHICLE_CMD_PX4_INTERNAL_START = 65537 # start of PX4 internal only vehicle commands (> UINT16_MAX)
|
||||||
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude|
|
uint32 VEHICLE_CMD_SET_GPS_GLOBAL_ORIGIN = 100000 # Sets the GPS coordinates of the vehicle local origin (0,0,0) position. |Empty|Empty|Empty|Empty|Latitude|Longitude|Altitude|
|
||||||
|
uint32 VEHICLE_CMD_SET_NAV_STATE = 100001 # Change mode by specifying nav_state directly. |nav_state|Empty|Empty|Empty|Empty|Empty|Empty|
|
||||||
|
|
||||||
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
|
uint8 VEHICLE_MOUNT_MODE_RETRACT = 0 # Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization |
|
||||||
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
|
uint8 VEHICLE_MOUNT_MODE_NEUTRAL = 1 # Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. |
|
||||||
|
|
|
@ -878,6 +878,18 @@ Commander::handle_command(const vehicle_command_s &cmd)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case vehicle_command_s::VEHICLE_CMD_SET_NAV_STATE: { // Used from ROS
|
||||||
|
uint8_t desired_nav_state = (uint8_t)(cmd.param1 + 0.5f);
|
||||||
|
|
||||||
|
if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd))) {
|
||||||
|
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
case vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM: {
|
case vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM: {
|
||||||
|
|
||||||
// Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints
|
// Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints
|
||||||
|
|
Loading…
Reference in New Issue