APMRover2: const correctness

This commit is contained in:
Pierre Kancir 2017-01-31 11:12:26 +01:00 committed by Grant Morphett
parent c41e695c98
commit 20cc336885
10 changed files with 35 additions and 37 deletions

View File

@ -119,7 +119,7 @@ void Rover::loop()
// wait for an INS sample // wait for an INS sample
ins.wait_for_sample(); ins.wait_for_sample();
uint32_t timer = AP_HAL::micros(); const uint32_t timer = AP_HAL::micros();
delta_us_fast_loop = timer - fast_loopTimer_us; delta_us_fast_loop = timer - fast_loopTimer_us;
G_Dt = delta_us_fast_loop * 1.0e-6f; G_Dt = delta_us_fast_loop * 1.0e-6f;
@ -405,7 +405,7 @@ void Rover::update_GPS_10Hz(void)
init_home(); init_home();
// set system clock for log timestamps // set system clock for log timestamps
uint64_t gps_timestamp = gps.time_epoch_usec(); const uint64_t gps_timestamp = gps.time_epoch_usec();
hal.util->set_system_clock(gps_timestamp); hal.util->set_system_clock(gps_timestamp);

View File

@ -7,7 +7,7 @@ void Rover::send_heartbeat(mavlink_channel_t chan)
{ {
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE; uint8_t system_status = MAV_STATE_ACTIVE;
uint32_t custom_mode = control_mode; const uint32_t custom_mode = control_mode;
if (failsafe.triggered != 0) { if (failsafe.triggered != 0) {
system_status = MAV_STATE_CRITICAL; system_status = MAV_STATE_CRITICAL;
@ -71,7 +71,7 @@ void Rover::send_heartbeat(mavlink_channel_t chan)
void Rover::send_attitude(mavlink_channel_t chan) void Rover::send_attitude(mavlink_channel_t chan)
{ {
Vector3f omega = ahrs.get_gyro(); const Vector3f omega = ahrs.get_gyro();
mavlink_msg_attitude_send( mavlink_msg_attitude_send(
chan, chan,
millis(), millis(),
@ -1498,7 +1498,7 @@ void Rover::mavlink_delay_cb()
in_mavlink_delay = true; in_mavlink_delay = true;
uint32_t tnow = millis(); const uint32_t tnow = millis();
if (tnow - last_1hz > 1000) { if (tnow - last_1hz > 1000) {
last_1hz = tnow; last_1hz = tnow;
gcs_send_message(MSG_HEARTBEAT); gcs_send_message(MSG_HEARTBEAT);

View File

@ -93,15 +93,13 @@ int8_t Rover::erase_logs(uint8_t argc, const Menu::arg *argv)
int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv) int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
{ {
uint16_t bits; uint16_t bits = 0;
if (argc != 2) { if (argc != 2) {
cliSerial->printf("missing log type\n"); cliSerial->printf("missing log type\n");
return(-1); return(-1);
} }
bits = 0;
// Macro to make the following code a bit easier on the eye. // Macro to make the following code a bit easier on the eye.
// Pass it the capitalised name of the log option, as defined // Pass it the capitalised name of the log option, as defined
// in defines.h but without the LOG_ prefix. It will check for // in defines.h but without the LOG_ prefix. It will check for
@ -236,7 +234,7 @@ struct PACKED log_Control_Tuning {
// Write a control tuning packet. Total length : 22 bytes // Write a control tuning packet. Total length : 22 bytes
void Rover::Log_Write_Control_Tuning() void Rover::Log_Write_Control_Tuning()
{ {
Vector3f accel = ins.get_accel(); const Vector3f accel = ins.get_accel();
struct log_Control_Tuning pkt = { struct log_Control_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG), LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
@ -279,7 +277,7 @@ void Rover::Log_Write_Nav_Tuning()
// Write an attitude packet // Write an attitude packet
void Rover::Log_Write_Attitude() void Rover::Log_Write_Attitude()
{ {
Vector3f targets(0.0f, 0.0f, 0.0f); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message const Vector3f targets(0.0f, 0.0f, 0.0f); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message
DataFlash.Log_Write_Attitude(ahrs, targets); DataFlash.Log_Write_Attitude(ahrs, targets);

View File

@ -599,7 +599,7 @@ void Rover::load_parameters(void)
cliSerial->printf("done.\n"); cliSerial->printf("done.\n");
} }
uint32_t before = micros(); const uint32_t before = micros();
// Load all auto-loaded EEPROM variables // Load all auto-loaded EEPROM variables
AP_Param::load_all(); AP_Param::load_all();

View File

@ -54,7 +54,7 @@ bool Rover::auto_check_trigger(void) {
} }
if (!is_zero(g.auto_kickstart)) { if (!is_zero(g.auto_kickstart)) {
float xaccel = ins.get_accel().x; const float xaccel = ins.get_accel().x;
if (xaccel >= g.auto_kickstart) { if (xaccel >= g.auto_kickstart) {
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Triggered AUTO xaccel=%.1f", static_cast<double>(xaccel)); gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Triggered AUTO xaccel=%.1f", static_cast<double>(xaccel));
auto_triggered = true; auto_triggered = true;
@ -70,7 +70,7 @@ bool Rover::auto_check_trigger(void) {
*/ */
bool Rover::use_pivot_steering(void) { bool Rover::use_pivot_steering(void) {
if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) { if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) {
int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100; const int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;
if (abs(bearing_error) > g.pivot_turn_angle) { if (abs(bearing_error) > g.pivot_turn_angle) {
return true; return true;
} }
@ -111,8 +111,8 @@ void Rover::calc_throttle(float target_speed) {
return; return;
} }
float throttle_base = (fabsf(target_speed) / g.speed_cruise) * g.throttle_cruise; const float throttle_base = (fabsf(target_speed) / g.speed_cruise) * g.throttle_cruise;
int throttle_target = throttle_base + throttle_nudge; const int throttle_target = throttle_base + throttle_nudge;
/* /*
reduce target speed in proportion to turning rate, up to the reduce target speed in proportion to turning rate, up to the
@ -123,15 +123,15 @@ void Rover::calc_throttle(float target_speed) {
// use g.speed_turn_gain for a 90 degree turn, and in proportion // use g.speed_turn_gain for a 90 degree turn, and in proportion
// for other turn angles // for other turn angles
int32_t turn_angle = wrap_180_cd(next_navigation_leg_cd - ahrs.yaw_sensor); const int32_t turn_angle = wrap_180_cd(next_navigation_leg_cd - ahrs.yaw_sensor);
float speed_turn_ratio = constrain_float(fabsf(turn_angle / 9000.0f), 0, 1); const float speed_turn_ratio = constrain_float(fabsf(turn_angle / 9000.0f), 0, 1);
float speed_turn_reduction = (100 - g.speed_turn_gain) * speed_turn_ratio * 0.01f; const float speed_turn_reduction = (100 - g.speed_turn_gain) * speed_turn_ratio * 0.01f;
float reduction = 1.0f - steer_rate * speed_turn_reduction; float reduction = 1.0f - steer_rate * speed_turn_reduction;
if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) { if (control_mode >= AUTO && wp_distance <= g.speed_turn_dist) {
// in auto-modes we reduce speed when approaching waypoints // in auto-modes we reduce speed when approaching waypoints
float reduction2 = 1.0f - speed_turn_reduction; const float reduction2 = 1.0f - speed_turn_reduction;
if (reduction2 < reduction) { if (reduction2 < reduction) {
reduction = reduction2; reduction = reduction2;
} }
@ -162,8 +162,8 @@ void Rover::calc_throttle(float target_speed) {
// We use a linear gain, with 0 gain at a ground speed error // We use a linear gain, with 0 gain at a ground speed error
// of braking_speederr, and 100% gain when groundspeed_error // of braking_speederr, and 100% gain when groundspeed_error
// is 2*braking_speederr // is 2*braking_speederr
float brake_gain = constrain_float(((-groundspeed_error)-g.braking_speederr)/g.braking_speederr, 0, 1); const float brake_gain = constrain_float(((-groundspeed_error)-g.braking_speederr)/g.braking_speederr, 0, 1);
int16_t braking_throttle = g.throttle_max * (g.braking_percent * 0.01f) * brake_gain; const int16_t braking_throttle = g.throttle_max * (g.braking_percent * 0.01f) * brake_gain;
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_int16(-braking_throttle, -g.throttle_max, -g.throttle_min)); SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_int16(-braking_throttle, -g.throttle_max, -g.throttle_min));
// temporarily set us in reverse to allow the PWM setting to // temporarily set us in reverse to allow the PWM setting to
@ -207,7 +207,7 @@ void Rover::calc_lateral_acceleration() {
// positive error = right turn // positive error = right turn
lateral_acceleration = nav_controller->lateral_acceleration(); lateral_acceleration = nav_controller->lateral_acceleration();
if (use_pivot_steering()) { if (use_pivot_steering()) {
int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100; const int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;
if (bearing_error > 0) { if (bearing_error > 0) {
lateral_acceleration = g.turn_max_g * GRAVITY_MSS; lateral_acceleration = g.turn_max_g * GRAVITY_MSS;
} else { } else {

View File

@ -137,7 +137,7 @@ void Rover::exit_mission()
bool Rover::verify_command_callback(const AP_Mission::Mission_Command& cmd) bool Rover::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{ {
if (control_mode == AUTO) { if (control_mode == AUTO) {
bool cmd_complete = verify_command(cmd); const bool cmd_complete = verify_command(cmd);
// send message to GCS // send message to GCS
if (cmd_complete) { if (cmd_complete) {
@ -304,7 +304,7 @@ bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
} }
// check if distance to the WP has changed and output new message if it has // check if distance to the WP has changed and output new message if it has
float dist_to_wp = get_distance(current_loc, next_WP); const float dist_to_wp = get_distance(current_loc, next_WP);
if (!is_equal(distance_past_wp, dist_to_wp)) { if (!is_equal(distance_past_wp, dist_to_wp)) {
distance_past_wp = dist_to_wp; distance_past_wp = dist_to_wp;
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed waypoint #%i. Distance %um", gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed waypoint #%i. Distance %um",
@ -356,7 +356,7 @@ bool Rover::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
// verify_loiter_time - check if we have loitered long enough // verify_loiter_time - check if we have loitered long enough
bool Rover::verify_loiter_time(const AP_Mission::Mission_Command& cmd) bool Rover::verify_loiter_time(const AP_Mission::Mission_Command& cmd)
{ {
bool result = verify_nav_wp(cmd); const bool result = verify_nav_wp(cmd);
if (result) { if (result) {
gcs_send_text(MAV_SEVERITY_WARNING, "Finished active loiter\n"); gcs_send_text(MAV_SEVERITY_WARNING, "Finished active loiter\n");
// if we have finished active loitering - turn it off // if we have finished active loitering - turn it off
@ -376,7 +376,7 @@ void Rover::nav_set_yaw_speed()
return; return;
} }
int32_t steering = steerController.get_steering_out_angle_error(guided_yaw_speed.turn_angle); const int32_t steering = steerController.get_steering_out_angle_error(guided_yaw_speed.turn_angle);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering); SRV_Channels::set_output_scaled(SRV_Channel::k_steering, steering);
// speed param in the message gives speed as a proportion of cruise speed. // speed param in the message gives speed as a proportion of cruise speed.

View File

@ -5,7 +5,7 @@ static const int16_t CH_7_PWM_TRIGGER = 1800;
void Rover::read_control_switch() void Rover::read_control_switch()
{ {
static bool switch_debouncer; static bool switch_debouncer;
uint8_t switchPosition = readSwitch(); const uint8_t switchPosition = readSwitch();
// If switchPosition = 255 this indicates that the mode control channel input was out of range // If switchPosition = 255 this indicates that the mode control channel input was out of range
// If we get this value we do not want to change modes. // If we get this value we do not want to change modes.
@ -49,7 +49,7 @@ void Rover::read_control_switch()
} }
uint8_t Rover::readSwitch(void) { uint8_t Rover::readSwitch(void) {
uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1); const uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) { if (pulsewidth <= 900 || pulsewidth >= 2200) {
return 255; // This is an error condition return 255; // This is an error condition
} }

View File

@ -19,7 +19,7 @@ void Rover::failsafe_check()
static uint16_t last_mainLoop_count; static uint16_t last_mainLoop_count;
static uint32_t last_timestamp; static uint32_t last_timestamp;
static bool in_failsafe; static bool in_failsafe;
uint32_t tnow = AP_HAL::micros(); const uint32_t tnow = AP_HAL::micros();
if (mainLoop_count != last_mainLoop_count) { if (mainLoop_count != last_mainLoop_count) {
// the main loop is running, all is OK // the main loop is running, all is OK

View File

@ -78,7 +78,7 @@ void Rover::rudder_arm_disarm_check()
if (!arming.is_armed()) { if (!arming.is_armed()) {
// when not armed, full right rudder starts arming counter // when not armed, full right rudder starts arming counter
if (channel_steer->get_control_in() > 4000) { if (channel_steer->get_control_in() > 4000) {
uint32_t now = millis(); const uint32_t now = millis();
if (rudder_arm_timer == 0 || if (rudder_arm_timer == 0 ||
now - rudder_arm_timer < 3000) { now - rudder_arm_timer < 3000) {
@ -99,7 +99,7 @@ void Rover::rudder_arm_disarm_check()
// This is disabled for skid steering otherwise when tring to turn a skid steering rover around // This is disabled for skid steering otherwise when tring to turn a skid steering rover around
// the rover would disarm // the rover would disarm
if (channel_steer->get_control_in() < -4000) { if (channel_steer->get_control_in() < -4000) {
uint32_t now = millis(); const uint32_t now = millis();
if (rudder_arm_timer == 0 || if (rudder_arm_timer == 0 ||
now - rudder_arm_timer < 3000) { now - rudder_arm_timer < 3000) {
@ -154,10 +154,10 @@ void Rover::read_radio()
motor2 = throttle - 0.5*steering motor2 = throttle - 0.5*steering
*/ */
float motor1 = channel_steer->norm_input(); const float motor1 = channel_steer->norm_input();
float motor2 = channel_throttle->norm_input(); const float motor2 = channel_throttle->norm_input();
float steering_scaled = motor1 - motor2; const float steering_scaled = motor1 - motor2;
float throttle_scaled = 0.5f * (motor1 + motor2); const float throttle_scaled = 0.5f * (motor1 + motor2);
int16_t steer = channel_steer->get_radio_trim(); int16_t steer = channel_steer->get_radio_trim();
int16_t thr = channel_throttle->get_radio_trim(); int16_t thr = channel_throttle->get_radio_trim();

View File

@ -513,7 +513,7 @@ void Rover::notify_mode(enum mode new_mode)
*/ */
uint8_t Rover::check_digital_pin(uint8_t pin) uint8_t Rover::check_digital_pin(uint8_t pin)
{ {
int8_t dpin = hal.gpio->analogPinToDigitalPin(pin); const int8_t dpin = hal.gpio->analogPinToDigitalPin(pin);
if (dpin == -1) { if (dpin == -1) {
return 0; return 0;
} }
@ -534,7 +534,7 @@ bool Rover::should_log(uint32_t mask)
if (!(mask & g.log_bitmask) || in_mavlink_delay) { if (!(mask & g.log_bitmask) || in_mavlink_delay) {
return false; return false;
} }
bool ret = hal.util->get_soft_armed() || DataFlash.log_while_disarmed(); const bool ret = hal.util->get_soft_armed() || DataFlash.log_while_disarmed();
if (ret && !DataFlash.logging_started() && !in_log_download) { if (ret && !DataFlash.logging_started() && !in_log_download) {
start_logging(); start_logging();
} }