mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
APMRover2: correct some style
This commit is contained in:
parent
b634fe548d
commit
c41e695c98
@ -518,7 +518,6 @@ void Rover::update_current_mode(void)
|
||||
we set the exact value in set_servos(), but it helps for
|
||||
logging
|
||||
*/
|
||||
in_auto_reverse = false;
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, channel_throttle->get_control_in());
|
||||
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, channel_steer->get_control_in());
|
||||
|
||||
|
@ -180,6 +180,7 @@ void Rover::send_vfr_hud(mavlink_channel_t chan)
|
||||
ahrs.groundspeed(),
|
||||
(ahrs.yaw_sensor / 100) % 360,
|
||||
static_cast<uint16_t>(100 * fabsf(SRV_Channels::get_output_norm(SRV_Channel::k_throttle))), // WRONG float to uint16
|
||||
current_loc.alt / 100.0f,
|
||||
0);
|
||||
}
|
||||
|
||||
|
@ -7,7 +7,6 @@
|
||||
|
||||
class GCS_MAVLINK_Rover : public GCS_MAVLINK
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
void data_stream_send(void) override;
|
||||
@ -23,5 +22,4 @@ private:
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
||||
bool try_send_message(enum ap_message id) override;
|
||||
|
||||
};
|
||||
|
@ -279,7 +279,7 @@ void Rover::Log_Write_Nav_Tuning()
|
||||
// Write an attitude packet
|
||||
void Rover::Log_Write_Attitude()
|
||||
{
|
||||
Vector3f targets(0, 0, 0); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message
|
||||
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);
|
||||
|
||||
|
@ -599,7 +599,7 @@ void Rover::load_parameters(void)
|
||||
cliSerial->printf("done.\n");
|
||||
}
|
||||
|
||||
unsigned long before = micros();
|
||||
uint32_t before = micros();
|
||||
// Load all auto-loaded EEPROM variables
|
||||
AP_Param::load_all();
|
||||
|
||||
|
@ -288,7 +288,7 @@ public:
|
||||
Parameters() :
|
||||
// PID controller initial P initial I initial D initial imax
|
||||
//-----------------------------------------------------------------------------------
|
||||
pidSpeedThrottle (0.7, 0.2, 0.2, 4000)
|
||||
pidSpeedThrottle (0.7f, 0.2f, 0.2f, 4000)
|
||||
{}
|
||||
};
|
||||
|
||||
@ -318,7 +318,6 @@ public:
|
||||
// advanced failsafe library
|
||||
AP_AdvancedFailsafe_Rover afs;
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
@ -49,6 +49,6 @@ Rover::Rover(void) :
|
||||
frsky_telemetry(ahrs, battery, sonar),
|
||||
#endif
|
||||
home(ahrs.get_home()),
|
||||
G_Dt(0.02)
|
||||
G_Dt(0.02f)
|
||||
{
|
||||
}
|
||||
|
@ -305,7 +305,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
|
||||
float dist_to_wp = get_distance(current_loc, next_WP);
|
||||
if ((uint32_t)distance_past_wp != (uint32_t)dist_to_wp) {
|
||||
if (!is_equal(distance_past_wp, dist_to_wp)) {
|
||||
distance_past_wp = dist_to_wp;
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Passed waypoint #%i. Distance %um",
|
||||
static_cast<uint32_t>(cmd.index),
|
||||
@ -432,12 +432,12 @@ bool Rover::verify_within_distance()
|
||||
|
||||
void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
if (cmd.content.speed.target_ms > 0) {
|
||||
if (cmd.content.speed.target_ms > 0.0f) {
|
||||
g.speed_cruise.set(cmd.content.speed.target_ms);
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Cruise speed: %.1f m/s", static_cast<double>(g.speed_cruise.get()));
|
||||
}
|
||||
|
||||
if (cmd.content.speed.throttle_pct > 0 && cmd.content.speed.throttle_pct <= 100) {
|
||||
if (cmd.content.speed.throttle_pct > 0.0f && cmd.content.speed.throttle_pct <= 100.0f) {
|
||||
g.throttle_cruise.set(cmd.content.speed.throttle_pct);
|
||||
gcs_send_text_fmt(MAV_SEVERITY_INFO, "Cruise throttle: %.1f", g.throttle_cruise.get());
|
||||
}
|
||||
|
@ -158,6 +158,7 @@ void Rover::read_radio()
|
||||
float motor2 = channel_throttle->norm_input();
|
||||
float steering_scaled = motor1 - motor2;
|
||||
float throttle_scaled = 0.5f * (motor1 + motor2);
|
||||
|
||||
int16_t steer = channel_steer->get_radio_trim();
|
||||
int16_t thr = channel_throttle->get_radio_trim();
|
||||
if (steering_scaled > 0.0f) {
|
||||
|
Loading…
Reference in New Issue
Block a user