mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
Merge branch 'navigator_new' into navigator_new_vector
This commit is contained in:
@@ -186,7 +186,7 @@ then
|
||||
tone_alarm MBABGP
|
||||
if px4io forceupdate 14662 $io_file
|
||||
then
|
||||
usleep 200000
|
||||
usleep 500000
|
||||
if px4io start
|
||||
then
|
||||
echo "PX4IO restart OK"
|
||||
@@ -196,7 +196,8 @@ then
|
||||
echo "PX4IO restart failed"
|
||||
echo "PX4IO restart failed" >> $logfile
|
||||
tone_alarm MNGGG
|
||||
sh /etc/init.d/rc.error
|
||||
sleep 10
|
||||
reboot
|
||||
fi
|
||||
else
|
||||
echo "PX4IO update failed"
|
||||
|
||||
@@ -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) {
|
||||
|
||||
@@ -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
@@ -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
|
||||
|
||||
@@ -1176,9 +1176,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);
|
||||
|
||||
@@ -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;
|
||||
};
|
||||
@@ -297,7 +297,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"),
|
||||
LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
|
||||
|
||||
@@ -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 */
|
||||
|
||||
@@ -148,6 +148,7 @@ esc_calib_main(int argc, char *argv[])
|
||||
|
||||
case 'l':
|
||||
/* Read in custom low value */
|
||||
pwm_low = strtoul(optarg, &ep, 0);
|
||||
if (*ep != '\0' || pwm_low < PWM_LOWEST_MIN || pwm_low > PWM_HIGHEST_MIN)
|
||||
usage("low PWM invalid");
|
||||
break;
|
||||
|
||||
Reference in New Issue
Block a user