AP_Mission: support MAV_CMD_NAV_VELOCITY msg

This commit is contained in:
Randy Mackay 2014-06-02 18:02:04 +09:00
parent 34b91496f9
commit fe8a5be802
2 changed files with 24 additions and 0 deletions

View File

@ -500,6 +500,13 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
cmd.content.nav_guided.horiz_max = packet.param4; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
break;
case MAV_CMD_NAV_VELOCITY: // MAV ID: 91
cmd.p1 = packet.param1; // frame - unused
cmd.content.nav_velocity.x = packet.x; // lat (i.e. north) velocity in m/s
cmd.content.nav_velocity.y = packet.y; // lon (i.e. east) velocity in m/s
cmd.content.nav_velocity.z = packet.z; // vertical (i.e. up) velocity in m/s
break;
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
cmd.content.delay.seconds = packet.param1; // delay in seconds
break;
@ -733,6 +740,13 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
packet.param4 = cmd.content.nav_guided.horiz_max; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
break;
case MAV_CMD_NAV_VELOCITY: // MAV ID: 91
packet.param1 = cmd.p1; // frame - unused
packet.x = cmd.content.nav_velocity.x; // lat (i.e. north) velocity in m/s
packet.y = cmd.content.nav_velocity.y; // lon (i.e. east) velocity in m/s
packet.z = cmd.content.nav_velocity.z; // vertical (i.e. up) velocity in m/s
break;
case MAV_CMD_CONDITION_DELAY: // MAV ID: 112
packet.param1 = cmd.content.delay.seconds; // delay in seconds
break;

View File

@ -50,6 +50,13 @@ public:
float horiz_max; // max horizontal distance the vehicle can move before the command will be aborted. 0 for no horizontal limit
};
// nav velocity command
struct PACKED Nav_Velocity_Command {
float x; // lat (i.e. north) velocity in m/s
float y; // lon (i.e. east) velocity in m/s
float z; // vertical velocity in m/s
};
// jump command structure
struct PACKED Jump_Command {
uint16_t target; // target command id
@ -117,6 +124,9 @@ public:
// Nav_Guided_Command
Nav_Guided_Command nav_guided;
// Nav_Velocity_Command
Nav_Velocity_Command nav_velocity;
// jump structure
Jump_Command jump;