forked from Archive/PX4-Autopilot
Merge remote-tracking branch 'upstream/master' into mavlinkexternalsetpoints
This commit is contained in:
commit
038f4f6203
|
@ -197,8 +197,10 @@ public:
|
||||||
* Print IO status.
|
* Print IO status.
|
||||||
*
|
*
|
||||||
* Print all relevant IO status information
|
* Print all relevant IO status information
|
||||||
|
*
|
||||||
|
* @param extended_status Shows more verbose information (in particular RC config)
|
||||||
*/
|
*/
|
||||||
void print_status();
|
void print_status(bool extended_status);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Fetch and print debug console output.
|
* Fetch and print debug console output.
|
||||||
|
@ -1850,7 +1852,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
|
||||||
}
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
PX4IO::print_status()
|
PX4IO::print_status(bool extended_status)
|
||||||
{
|
{
|
||||||
/* basic configuration */
|
/* basic configuration */
|
||||||
printf("protocol %u hardware %u bootloader %u buffer %uB crc 0x%04x%04x\n",
|
printf("protocol %u hardware %u bootloader %u buffer %uB crc 0x%04x%04x\n",
|
||||||
|
@ -2013,19 +2015,21 @@ PX4IO::print_status()
|
||||||
printf("\n");
|
printf("\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
for (unsigned i = 0; i < _max_rc_input; i++) {
|
if (extended_status) {
|
||||||
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
|
for (unsigned i = 0; i < _max_rc_input; i++) {
|
||||||
uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
|
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
|
||||||
printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
|
uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
|
||||||
i,
|
printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
|
||||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
|
i,
|
||||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
|
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
|
||||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
|
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
|
||||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
|
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
|
||||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
|
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
|
||||||
options,
|
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
|
||||||
((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
|
options,
|
||||||
((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
|
((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
|
||||||
|
((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
printf("failsafe");
|
printf("failsafe");
|
||||||
|
@ -2853,7 +2857,7 @@ monitor(void)
|
||||||
if (g_dev != nullptr) {
|
if (g_dev != nullptr) {
|
||||||
|
|
||||||
printf("\033[2J\033[H"); /* move cursor home and clear screen */
|
printf("\033[2J\033[H"); /* move cursor home and clear screen */
|
||||||
(void)g_dev->print_status();
|
(void)g_dev->print_status(false);
|
||||||
(void)g_dev->print_debug();
|
(void)g_dev->print_debug();
|
||||||
printf("\n\n\n[ Use 'px4io debug <N>' for more output. Hit <enter> three times to exit monitor mode ]\n");
|
printf("\n\n\n[ Use 'px4io debug <N>' for more output. Hit <enter> three times to exit monitor mode ]\n");
|
||||||
|
|
||||||
|
@ -3119,7 +3123,7 @@ px4io_main(int argc, char *argv[])
|
||||||
if (!strcmp(argv[1], "status")) {
|
if (!strcmp(argv[1], "status")) {
|
||||||
|
|
||||||
printf("[px4io] loaded\n");
|
printf("[px4io] loaded\n");
|
||||||
g_dev->print_status();
|
g_dev->print_status(true);
|
||||||
|
|
||||||
exit(0);
|
exit(0);
|
||||||
}
|
}
|
||||||
|
|
|
@ -240,9 +240,9 @@ PX4IO_Uploader::upload(const char *filenames[])
|
||||||
close(_io_fd);
|
close(_io_fd);
|
||||||
_io_fd = -1;
|
_io_fd = -1;
|
||||||
|
|
||||||
// sleep for enough time for the IO chip to boot. This makes
|
// sleep for enough time for the IO chip to boot. This makes
|
||||||
// forceupdate more reliably startup IO again after update
|
// forceupdate more reliably startup IO again after update
|
||||||
up_udelay(100*1000);
|
up_udelay(100*1000);
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
|
@ -412,7 +412,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
|
||||||
/* if HIL got enabled, reset battery status state */
|
/* if HIL got enabled, reset battery status state */
|
||||||
if (hil_ret == OK && status->hil_state == HIL_STATE_ON) {
|
if (hil_ret == OK && status->hil_state == HIL_STATE_ON) {
|
||||||
/* reset the arming mode to disarmed */
|
/* reset the arming mode to disarmed */
|
||||||
arming_res = arming_state_transition(status, safety, ARMING_STATE_STANDBY, armed);
|
arming_res = arming_state_transition(status, safety, ARMING_STATE_STANDBY, armed, mavlink_fd);
|
||||||
|
|
||||||
if (arming_res != TRANSITION_DENIED) {
|
if (arming_res != TRANSITION_DENIED) {
|
||||||
mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
|
mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
|
||||||
|
@ -945,8 +945,8 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
|
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
|
||||||
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
|
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
|
||||||
|
|
||||||
if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) {
|
if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) {
|
||||||
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch");
|
mavlink_log_info(mavlink_fd, "#audio DISARMED by safety switch");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1149,10 +1149,10 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
|
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
|
||||||
|
|
||||||
if (armed.armed) {
|
if (armed.armed) {
|
||||||
arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
|
arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, mavlink_fd);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
|
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, mavlink_fd);
|
||||||
}
|
}
|
||||||
|
|
||||||
status_changed = true;
|
status_changed = true;
|
||||||
|
@ -1163,7 +1163,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
/* If in INIT state, try to proceed to STANDBY state */
|
/* If in INIT state, try to proceed to STANDBY state */
|
||||||
if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
|
if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
|
||||||
// XXX check for sensors
|
// XXX check for sensors
|
||||||
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
|
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
// XXX: Add emergency stuff if sensors are lost
|
// XXX: Add emergency stuff if sensors are lost
|
||||||
|
@ -1217,7 +1217,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
|
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
|
||||||
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
|
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
|
||||||
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
|
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
|
||||||
arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed);
|
arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd);
|
||||||
stick_off_counter = 0;
|
stick_off_counter = 0;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
@ -1239,7 +1239,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||||
print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first.");
|
print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first.");
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
|
arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd);
|
||||||
}
|
}
|
||||||
|
|
||||||
stick_on_counter = 0;
|
stick_on_counter = 0;
|
||||||
|
@ -1941,7 +1941,7 @@ void *commander_low_prio_loop(void *arg)
|
||||||
/* try to go to INIT/PREFLIGHT arming state */
|
/* try to go to INIT/PREFLIGHT arming state */
|
||||||
|
|
||||||
// XXX disable interrupts in arming_state_transition
|
// XXX disable interrupts in arming_state_transition
|
||||||
if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed)) {
|
if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, mavlink_fd)) {
|
||||||
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
|
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -2004,7 +2004,7 @@ void *commander_low_prio_loop(void *arg)
|
||||||
tune_negative(true);
|
tune_negative(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
|
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
|
@ -57,7 +57,7 @@ typedef enum {
|
||||||
} transition_result_t;
|
} transition_result_t;
|
||||||
|
|
||||||
transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
|
transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
|
||||||
arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd = 0);
|
arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd);
|
||||||
|
|
||||||
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
|
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
|
||||||
|
|
||||||
|
|
|
@ -707,14 +707,21 @@ FixedwingAttitudeControl::task_main()
|
||||||
float throttle_sp = 0.0f;
|
float throttle_sp = 0.0f;
|
||||||
|
|
||||||
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
|
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
|
||||||
|
/* read in attitude setpoint from attitude setpoint uorb topic */
|
||||||
roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
|
roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
|
||||||
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
|
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
|
||||||
throttle_sp = _att_sp.thrust;
|
throttle_sp = _att_sp.thrust;
|
||||||
|
|
||||||
/* reset integrals where needed */
|
/* reset integrals where needed */
|
||||||
if (_att_sp.roll_reset_integral)
|
if (_att_sp.roll_reset_integral) {
|
||||||
_roll_ctrl.reset_integrator();
|
_roll_ctrl.reset_integrator();
|
||||||
|
}
|
||||||
|
if (_att_sp.pitch_reset_integral) {
|
||||||
|
_pitch_ctrl.reset_integrator();
|
||||||
|
}
|
||||||
|
if (_att_sp.yaw_reset_integral) {
|
||||||
|
_yaw_ctrl.reset_integrator();
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
/*
|
/*
|
||||||
* Scale down roll and pitch as the setpoints are radians
|
* Scale down roll and pitch as the setpoints are radians
|
||||||
|
|
|
@ -841,6 +841,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||||
/* current waypoint (the one currently heading for) */
|
/* current waypoint (the one currently heading for) */
|
||||||
math::Vector<2> curr_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
|
math::Vector<2> curr_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
|
||||||
|
|
||||||
|
/* Initialize attitude controller integrator reset flags to 0 */
|
||||||
|
_att_sp.roll_reset_integral = false;
|
||||||
|
_att_sp.pitch_reset_integral = false;
|
||||||
|
_att_sp.yaw_reset_integral = false;
|
||||||
|
|
||||||
/* previous waypoint */
|
/* previous waypoint */
|
||||||
math::Vector<2> prev_wp;
|
math::Vector<2> prev_wp;
|
||||||
|
@ -1020,15 +1024,21 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||||
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) {
|
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) {
|
||||||
|
|
||||||
/* Perform launch detection */
|
/* Perform launch detection */
|
||||||
// warnx("Launch detection running");
|
|
||||||
if(!launch_detected) { //do not do further checks once a launch was detected
|
if(!launch_detected) { //do not do further checks once a launch was detected
|
||||||
if (launchDetector.launchDetectionEnabled()) {
|
if (launchDetector.launchDetectionEnabled()) {
|
||||||
static hrt_abstime last_sent = 0;
|
static hrt_abstime last_sent = 0;
|
||||||
if(hrt_absolute_time() - last_sent > 4e6) {
|
if(hrt_absolute_time() - last_sent > 4e6) {
|
||||||
// warnx("Launch detection running");
|
|
||||||
mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
|
mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
|
||||||
last_sent = hrt_absolute_time();
|
last_sent = hrt_absolute_time();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* Tell the attitude controller to stop integrating while we are waiting
|
||||||
|
* for the launch */
|
||||||
|
_att_sp.roll_reset_integral = true;
|
||||||
|
_att_sp.pitch_reset_integral = true;
|
||||||
|
_att_sp.yaw_reset_integral = true;
|
||||||
|
|
||||||
|
/* Detect launch */
|
||||||
launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
|
launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
|
||||||
if (launchDetector.getLaunchDetected()) {
|
if (launchDetector.getLaunchDetected()) {
|
||||||
launch_detected = true;
|
launch_detected = true;
|
||||||
|
|
|
@ -1555,32 +1555,36 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
||||||
/* delete stream */
|
/* delete stream */
|
||||||
LL_DELETE(_streams, stream);
|
LL_DELETE(_streams, stream);
|
||||||
delete stream;
|
delete stream;
|
||||||
|
warnx("deleted stream %s", stream->get_name());
|
||||||
}
|
}
|
||||||
|
|
||||||
return OK;
|
return OK;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (interval > 0) {
|
if (interval == 0) {
|
||||||
/* search for stream with specified name in supported streams list */
|
/* stream was not active and is requested to be disabled, do nothing */
|
||||||
for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
|
|
||||||
|
|
||||||
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
|
||||||
/* create new instance */
|
|
||||||
stream = streams_list[i]->new_instance();
|
|
||||||
stream->set_channel(get_channel());
|
|
||||||
stream->set_interval(interval);
|
|
||||||
stream->subscribe(this);
|
|
||||||
LL_APPEND(_streams, stream);
|
|
||||||
return OK;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
/* stream not found, nothing to disable */
|
|
||||||
return OK;
|
return OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/* search for stream with specified name in supported streams list */
|
||||||
|
for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
|
||||||
|
|
||||||
|
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
||||||
|
/* create new instance */
|
||||||
|
stream = streams_list[i]->new_instance();
|
||||||
|
stream->set_channel(get_channel());
|
||||||
|
stream->set_interval(interval);
|
||||||
|
stream->subscribe(this);
|
||||||
|
LL_APPEND(_streams, stream);
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* if we reach here, the stream list does not contain the stream */
|
||||||
|
warnx("stream %s not found", stream_name);
|
||||||
|
|
||||||
return ERROR;
|
return ERROR;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -226,19 +226,21 @@ protected:
|
||||||
struct vehicle_status_s status;
|
struct vehicle_status_s status;
|
||||||
struct position_setpoint_triplet_s pos_sp_triplet;
|
struct position_setpoint_triplet_s pos_sp_triplet;
|
||||||
|
|
||||||
if (status_sub->update(&status) && pos_sp_triplet_sub->update(&pos_sp_triplet)) {
|
/* always send the heartbeat, independent of the update status of the topics */
|
||||||
uint8_t mavlink_state = 0;
|
(void)status_sub->update(&status);
|
||||||
uint8_t mavlink_base_mode = 0;
|
(void)pos_sp_triplet_sub->update(&pos_sp_triplet);
|
||||||
uint32_t mavlink_custom_mode = 0;
|
|
||||||
get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
|
|
||||||
|
|
||||||
mavlink_msg_heartbeat_send(_channel,
|
uint8_t mavlink_state = 0;
|
||||||
mavlink_system.type,
|
uint8_t mavlink_base_mode = 0;
|
||||||
MAV_AUTOPILOT_PX4,
|
uint32_t mavlink_custom_mode = 0;
|
||||||
mavlink_base_mode,
|
get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
|
||||||
mavlink_custom_mode,
|
|
||||||
mavlink_state);
|
mavlink_msg_heartbeat_send(_channel,
|
||||||
}
|
mavlink_system.type,
|
||||||
|
MAV_AUTOPILOT_PX4,
|
||||||
|
mavlink_base_mode,
|
||||||
|
mavlink_custom_mode,
|
||||||
|
mavlink_state);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -1275,6 +1277,7 @@ protected:
|
||||||
// New message
|
// New message
|
||||||
mavlink_msg_rc_channels_send(_channel,
|
mavlink_msg_rc_channels_send(_channel,
|
||||||
rc.timestamp_publication / 1000,
|
rc.timestamp_publication / 1000,
|
||||||
|
rc.channel_count,
|
||||||
((rc.channel_count > 0) ? rc.values[0] : UINT16_MAX),
|
((rc.channel_count > 0) ? rc.values[0] : UINT16_MAX),
|
||||||
((rc.channel_count > 1) ? rc.values[1] : UINT16_MAX),
|
((rc.channel_count > 1) ? rc.values[1] : UINT16_MAX),
|
||||||
((rc.channel_count > 2) ? rc.values[2] : UINT16_MAX),
|
((rc.channel_count > 2) ? rc.values[2] : UINT16_MAX),
|
||||||
|
@ -1293,7 +1296,6 @@ protected:
|
||||||
((rc.channel_count > 15) ? rc.values[15] : UINT16_MAX),
|
((rc.channel_count > 15) ? rc.values[15] : UINT16_MAX),
|
||||||
((rc.channel_count > 16) ? rc.values[16] : UINT16_MAX),
|
((rc.channel_count > 16) ? rc.values[16] : UINT16_MAX),
|
||||||
((rc.channel_count > 17) ? rc.values[17] : UINT16_MAX),
|
((rc.channel_count > 17) ? rc.values[17] : UINT16_MAX),
|
||||||
rc.channel_count,
|
|
||||||
rc.rssi);
|
rc.rssi);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1625,7 +1627,7 @@ StreamListItem *streams_list[] = {
|
||||||
new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
|
new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static),
|
new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static),
|
new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static),
|
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
|
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
|
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
|
||||||
new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
|
new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
|
||||||
|
|
|
@ -301,7 +301,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
|
||||||
case PC_ELAPSED: {
|
case PC_ELAPSED: {
|
||||||
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
|
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
|
||||||
|
|
||||||
dprintf(fd, "%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
|
dprintf(fd, "%s: %llu events, %lluus elapsed, %lluus avg, min %lluus max %lluus\n",
|
||||||
handle->name,
|
handle->name,
|
||||||
pce->event_count,
|
pce->event_count,
|
||||||
pce->time_total,
|
pce->time_total,
|
||||||
|
@ -314,7 +314,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
|
||||||
case PC_INTERVAL: {
|
case PC_INTERVAL: {
|
||||||
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
|
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
|
||||||
|
|
||||||
dprintf(fd, "%s: %llu events, %llu avg, min %lluus max %lluus\n",
|
dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus\n",
|
||||||
handle->name,
|
handle->name,
|
||||||
pci->event_count,
|
pci->event_count,
|
||||||
(pci->time_last - pci->time_first) / pci->event_count,
|
(pci->time_last - pci->time_first) / pci->event_count,
|
||||||
|
|
|
@ -72,6 +72,8 @@ struct vehicle_attitude_setpoint_s {
|
||||||
float thrust; /**< Thrust in Newton the power system should generate */
|
float thrust; /**< Thrust in Newton the power system should generate */
|
||||||
|
|
||||||
bool roll_reset_integral; /**< Reset roll integral part (navigation logic change) */
|
bool roll_reset_integral; /**< Reset roll integral part (navigation logic change) */
|
||||||
|
bool pitch_reset_integral; /**< Reset pitch integral part (navigation logic change) */
|
||||||
|
bool yaw_reset_integral; /**< Reset yaw integral part (navigation logic change) */
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue