Improve config and mapping

This commit is contained in:
Lorenz Meier
2015-05-24 20:10:35 +02:00
parent 2bb655c46c
commit 009815deb0
4 changed files with 27 additions and 17 deletions
+1 -1
View File
@@ -126,7 +126,7 @@ bool rc_signal_lost # true if RC reception lost
uint64 rc_signal_lost_timestamp # Time at which the RC reception was lost
bool rc_signal_lost_cmd # true if RC lost mode is commanded
bool rc_input_blocked # set if RC input should be ignored temporarily
bool rc_input_off # set if RC input should be disabled completely
uint8 rc_input_off # set to 1 to disable the RC input, 2 to enable manual control to RC in mapping.
bool data_link_lost # datalink to GCS lost
bool data_link_lost_cmd # datalink to GCS lost mode commanded
+7 -5
View File
@@ -889,7 +889,7 @@ int commander_thread_main(int argc, char *argv[])
status.condition_landed = true; // initialize to safe value
// We want to accept RC inputs as default
status.rc_input_blocked = false;
status.rc_input_off = false;
status.rc_input_off = vehicle_status_s::RC_IN_MODE_DEFAULT;
status.main_state =vehicle_status_s::MAIN_STATE_MANUAL;
status.nav_state = vehicle_status_s::NAVIGATION_STATE_MANUAL;
status.arming_state = vehicle_status_s::ARMING_STATE_INIT;
@@ -1237,7 +1237,7 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_datalink_loss_timeout, &datalink_loss_timeout);
param_get(_param_rc_loss_timeout, &rc_loss_timeout);
param_get(_param_rc_in_off, &rc_in_off);
status.rc_input_off = (rc_in_off == vehicle_status_s::RC_IN_MODE_OFF);
status.rc_input_off = rc_in_off;
param_get(_param_datalink_regain_timeout, &datalink_regain_timeout);
param_get(_param_ef_throttle_thres, &ef_throttle_thres);
param_get(_param_ef_current2throttle_thres, &ef_current2throttle_thres);
@@ -1310,7 +1310,8 @@ int commander_thread_main(int argc, char *argv[])
}
/* provide RC and sensor status feedback to the user */
(void)Commander::preflightCheck(mavlink_fd, true, true, true, true, chAirspeed, !status.rc_input_off, !status.circuit_breaker_engaged_gpsfailure_check);
(void)Commander::preflightCheck(mavlink_fd, true, true, true, true, chAirspeed,
!(status.rc_input_off == vehicle_status_s::RC_IN_MODE_OFF), !status.circuit_breaker_engaged_gpsfailure_check);
}
telemetry_last_heartbeat[i] = telemetry.heartbeat_time;
@@ -1712,7 +1713,7 @@ int commander_thread_main(int argc, char *argv[])
} // no reset is done here on purpose, on geofence violation we want to stay in flighttermination
/* RC input check */
if (!status.rc_input_off && !status.rc_input_blocked && sp_man.timestamp != 0 &&
if (!(status.rc_input_off == vehicle_status_s::RC_IN_MODE_OFF) && !status.rc_input_blocked && sp_man.timestamp != 0 &&
hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) {
/* handle the case where RC signal was regained */
if (!status.rc_signal_found_once) {
@@ -2775,7 +2776,8 @@ void *commander_low_prio_loop(void *arg)
checkAirspeed = true;
}
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, !status.rc_input_off, !status.circuit_breaker_engaged_gpsfailure_check);
status.condition_system_sensors_initialized = Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed,
!(status.rc_input_off == vehicle_status_s::RC_IN_MODE_OFF), !status.circuit_breaker_engaged_gpsfailure_check);
arming_state_transition(&status, &safety, vehicle_status_s::ARMING_STATE_STANDBY, &armed, false /* fRunPreArmChecks */, mavlink_fd);
@@ -692,5 +692,5 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
checkAirspeed = true;
}
return !Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, !status->rc_input_off, !status->circuit_breaker_engaged_gpsfailure_check, true);
return !Commander::preflightCheck(mavlink_fd, true, true, true, true, checkAirspeed, !(status->rc_input_off == vehicle_status_s::RC_IN_MODE_OFF), !status->circuit_breaker_engaged_gpsfailure_check, true);
}
+18 -10
View File
@@ -904,6 +904,14 @@ static switch_pos_t decode_switch_pos(uint16_t buttons, int sw) {
return (buttons >> (sw * 2)) & 3;
}
static int decode_switch_pos_n(uint16_t buttons, int sw) {
if (buttons & (1 << sw)) {
return 1;
} else {
return 0;
}
}
void
MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
{
@@ -929,17 +937,17 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
rc.rc_ppm_frame_length = 0;
rc.input_source = RC_INPUT_SOURCE_MAVLINK;
rc.rssi = RC_INPUT_RSSI_MAX;
rc.values[0] = man.x * 500 + 1500;
rc.values[1] = man.y * 500 + 1500;
rc.values[2] = man.r / 2.0f + 1500;
rc.values[3] = man.z / 2.0f + 1500;
rc.values[0] = man.x / 2 + 1500;
rc.values[1] = man.y / 2 + 1500;
rc.values[2] = man.r / 2 + 1500;
rc.values[3] = man.z + 1000;
rc.values[4] = decode_switch_pos(man.buttons, 0) * 1000 + 1000;
rc.values[5] = decode_switch_pos(man.buttons, 1) * 1000 + 1000;
rc.values[6] = decode_switch_pos(man.buttons, 2) * 1000 + 1000;
rc.values[7] = decode_switch_pos(man.buttons, 3) * 1000 + 1000;
rc.values[8] = decode_switch_pos(man.buttons, 4) * 1000 + 1000;
rc.values[9] = decode_switch_pos(man.buttons, 5) * 1000 + 1000;
rc.values[4] = decode_switch_pos_n(man.buttons, 0) * 1000 + 1000;
rc.values[5] = decode_switch_pos_n(man.buttons, 1) * 1000 + 1000;
rc.values[6] = decode_switch_pos_n(man.buttons, 2) * 1000 + 1000;
rc.values[7] = decode_switch_pos_n(man.buttons, 3) * 1000 + 1000;
rc.values[8] = decode_switch_pos_n(man.buttons, 4) * 1000 + 1000;
rc.values[9] = decode_switch_pos_n(man.buttons, 5) * 1000 + 1000;
if (_rc_pub <= 0) {
_rc_pub = orb_advertise(ORB_ID(input_rc), &rc);