forked from Archive/PX4-Autopilot
Mission topic: make nav_cmd compatible to the mavlink command
This commit is contained in:
parent
1da7599541
commit
01df715f94
|
@ -78,7 +78,7 @@ void map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavl
|
|||
mission_item->yaw = mavlink_mission_item->param4*M_DEG_TO_RAD_F;
|
||||
mission_item->loiter_radius = fabsf(mavlink_mission_item->param3);
|
||||
mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
|
||||
mission_item->nav_cmd = NAV_CMD_WAYPOINT; // TODO correct
|
||||
mission_item->nav_cmd = mavlink_mission_item->command;
|
||||
mission_item->radius = mavlink_mission_item->param1;
|
||||
mission_item->time_inside = mavlink_mission_item->param2 / 1e3f; /* from milliseconds to seconds */
|
||||
mission_item->autocontinue = mavlink_mission_item->autocontinue;
|
||||
|
@ -93,7 +93,7 @@ void map_mission_item_to_mavlink_mission_item(const struct mission_item_s *missi
|
|||
mavlink_mission_item->z = mission_item->altitude;
|
||||
mavlink_mission_item->param4 = mission_item->yaw*M_RAD_TO_DEG_F;
|
||||
mavlink_mission_item->param3 = mission_item->loiter_radius*(float)mission_item->loiter_direction;
|
||||
mavlink_mission_item->command = MAV_CMD_NAV_WAYPOINT; // TODO add
|
||||
mavlink_mission_item->command = mission_item->nav_cmd;
|
||||
mavlink_mission_item->param1 = mission_item->radius;
|
||||
mavlink_mission_item->param2 = mission_item->time_inside * 1e3f; /* from seconds to milliseconds */
|
||||
mavlink_mission_item->autocontinue = mission_item->autocontinue;
|
||||
|
|
|
@ -46,14 +46,17 @@
|
|||
#include <stdbool.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
/* compatible to mavlink MAV_CMD */
|
||||
enum NAV_CMD {
|
||||
NAV_CMD_WAYPOINT = 0,
|
||||
NAV_CMD_LOITER_TURN_COUNT,
|
||||
NAV_CMD_LOITER_TIME_LIMIT,
|
||||
NAV_CMD_LOITER_UNLIMITED,
|
||||
NAV_CMD_RETURN_TO_LAUNCH,
|
||||
NAV_CMD_LAND,
|
||||
NAV_CMD_TAKEOFF
|
||||
NAV_CMD_WAYPOINT=16,
|
||||
NAV_CMD_LOITER_UNLIMITED=17,
|
||||
NAV_CMD_LOITER_TURN_COUNT=18,
|
||||
NAV_CMD_LOITER_TIME_LIMIT=19,
|
||||
NAV_CMD_RETURN_TO_LAUNCH=20,
|
||||
NAV_CMD_LAND=21,
|
||||
NAV_CMD_TAKEOFF=22,
|
||||
NAV_CMD_ROI=80,
|
||||
NAV_CMD_PATHPLANNING=81
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -76,7 +79,7 @@ struct mission_item_s
|
|||
float yaw; /**< in radians NED -PI..+PI */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
|
||||
enum NAV_CMD nav_cmd; /**< true if loitering is enabled */
|
||||
enum NAV_CMD nav_cmd; /**< navigation command */
|
||||
float radius; /**< radius in which the mission is accepted as reached in meters */
|
||||
float time_inside; /**< time that the MAV should stay inside the radius before advancing in seconds */
|
||||
bool autocontinue; /**< true if next waypoint should follow after this one */
|
||||
|
|
Loading…
Reference in New Issue