navigator: takeoff and mission fixes

This commit is contained in:
Anton Babushkin
2014-01-02 14:49:34 +04:00
parent 3c72c9bf7f
commit 74e2542c07
7 changed files with 166 additions and 164 deletions
@@ -1230,7 +1230,7 @@ FixedwingPositionControl::task_main()
}
/* XXX check if radius makes sense here */
float turn_distance = _l1_control.switch_distance(_mission_item_triplet.current.radius);
float turn_distance = _l1_control.switch_distance(_mission_item_triplet.current.acceptance_radius);
/* lazily publish navigation capabilities */
if (turn_distance != _nav_capabilities.turn_distance && turn_distance > 0) {
+2 -2
View File
@@ -143,7 +143,7 @@ int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavli
mission_item->pitch_min = mavlink_mission_item->param2;
break;
default:
mission_item->radius = mavlink_mission_item->param2;
mission_item->acceptance_radius = mavlink_mission_item->param2;
break;
}
@@ -173,7 +173,7 @@ int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *missio
mavlink_mission_item->param2 = mission_item->pitch_min;
break;
default:
mavlink_mission_item->param2 = mission_item->radius;
mavlink_mission_item->param2 = mission_item->acceptance_radius;
break;
}
File diff suppressed because it is too large Load Diff
+4 -2
View File
@@ -52,7 +52,9 @@
*/
PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 100.0f);
PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 10.0f); // default TAKEOFF altitude, slow descend from this altitude when landing in RTL mode
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 10.0f); // min altitude for going home in RTL mode
PARAM_DEFINE_FLOAT(NAV_TAAKEOFF_ALT, 10.0f); // default TAKEOFF altitude
PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing
PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode
+1 -3
View File
@@ -1161,9 +1161,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPSP.nav_cmd = buf.triplet.current.nav_cmd;
log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius;
log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction;
log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius;
log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction;
log_msg.body.log_GPSP.radius = buf.triplet.current.radius;
log_msg.body.log_GPSP.acceptance_radius = buf.triplet.current.acceptance_radius;
log_msg.body.log_GPSP.time_inside = buf.triplet.current.time_inside;
log_msg.body.log_GPSP.pitch_min = buf.triplet.current.pitch_min;
LOGBUFFER_WRITE_AND_COUNT(GPSP);
+2 -2
View File
@@ -217,7 +217,7 @@ struct log_GPSP_s {
uint8_t nav_cmd;
float loiter_radius;
int8_t loiter_direction;
float radius;
float acceptance_radius;
float time_inside;
float pitch_min;
};
@@ -287,7 +287,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
LOG_FORMAT(GPOS, "LLffff", "Lat,Lon,Alt,VelN,VelE,VelD"),
LOG_FORMAT(GPSP, "BLLffBfbfff", "AltRel,Lat,Lon,Alt,Yaw,NavCmd,LoitRad,LoitDir,Rad,TimeIn,pitMin"),
LOG_FORMAT(GPSP, "BLLffBfbfff", "AltRel,Lat,Lon,Alt,Yaw,NavCmd,LoitR,LoitDir,AccR,TimeIn,PitMin"),
LOG_FORMAT(ESC, "HBBBHHHHHHfH", "Counter,NumESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
/* system-level messages, ID >= 0x80 */
+1 -1
View File
@@ -87,7 +87,7 @@ struct mission_item_s
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; /**< navigation command */
float radius; /**< radius in which the mission is accepted as reached in meters */
float acceptance_radius; /**< default 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 */
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
bool autocontinue; /**< true if next waypoint should follow after this one */