mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: remove wheel_encoder_rpm
This commit is contained in:
parent
692281b273
commit
12f66acfb7
@ -272,14 +272,6 @@ void Rover::send_pid_tuning(mavlink_channel_t chan)
|
||||
}
|
||||
}
|
||||
|
||||
void Rover::send_wheel_encoder(mavlink_channel_t chan)
|
||||
{
|
||||
// send wheel encoder data using rpm message
|
||||
if (g2.wheel_encoder.enabled(0) || g2.wheel_encoder.enabled(1)) {
|
||||
mavlink_msg_rpm_send(chan, wheel_encoder_rpm[0], wheel_encoder_rpm[1]);
|
||||
}
|
||||
}
|
||||
|
||||
void Rover::send_wheel_encoder_distance(mavlink_channel_t chan)
|
||||
{
|
||||
// send wheel encoder data using wheel_distance message
|
||||
|
@ -313,10 +313,8 @@ struct PACKED log_WheelEncoder {
|
||||
uint64_t time_us;
|
||||
float distance_0;
|
||||
uint8_t quality_0;
|
||||
float rpm_0;
|
||||
float distance_1;
|
||||
uint8_t quality_1;
|
||||
float rpm_1;
|
||||
};
|
||||
|
||||
// log wheel encoder information
|
||||
@ -331,10 +329,8 @@ void Rover::Log_Write_WheelEncoder()
|
||||
time_us : AP_HAL::micros64(),
|
||||
distance_0 : g2.wheel_encoder.get_distance(0),
|
||||
quality_0 : (uint8_t)constrain_float(g2.wheel_encoder.get_signal_quality(0), 0.0f, 100.0f),
|
||||
rpm_0 : wheel_encoder_rpm[0],
|
||||
distance_1 : g2.wheel_encoder.get_distance(1),
|
||||
quality_1 : (uint8_t)constrain_float(g2.wheel_encoder.get_signal_quality(1), 0.0f, 100.0f),
|
||||
rpm_1 : wheel_encoder_rpm[1]
|
||||
quality_1 : (uint8_t)constrain_float(g2.wheel_encoder.get_signal_quality(1), 0.0f, 100.0f)
|
||||
};
|
||||
logger.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -370,7 +366,7 @@ const LogStructure Rover::log_structure[] = {
|
||||
{ LOG_ERROR_MSG, sizeof(log_Error),
|
||||
"ERR", "QBB", "TimeUS,Subsys,ECode", "s--", "F--" },
|
||||
{ LOG_WHEELENCODER_MSG, sizeof(log_WheelEncoder),
|
||||
"WENC", "Qfbffbf", "TimeUS,Dist0,Qual0,RPM0,Dist1,Qual1,RPM1", "sm-qm-q", "F0--0--" },
|
||||
"WENC", "Qfbfb", "TimeUS,Dist0,Qual0,Dist1,Qual1", "sm-m-", "F0-0-" },
|
||||
};
|
||||
|
||||
void Rover::log_init(void)
|
||||
|
@ -343,7 +343,6 @@ private:
|
||||
float wheel_encoder_last_distance_m[WHEELENCODER_MAX_INSTANCES]; // distance in meters at time of last update to EKF (for reporting to GCS)
|
||||
uint32_t wheel_encoder_last_update_ms[WHEELENCODER_MAX_INSTANCES]; // system time of last ping from each encoder
|
||||
uint32_t wheel_encoder_last_ekf_update_ms; // system time of last encoder data push to EKF
|
||||
float wheel_encoder_rpm[WHEELENCODER_MAX_INSTANCES]; // for reporting to GCS
|
||||
|
||||
// True when we are doing motor test
|
||||
bool motor_test;
|
||||
@ -446,7 +445,6 @@ private:
|
||||
void send_servo_out(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void send_wheel_encoder(mavlink_channel_t chan);
|
||||
void send_wheel_encoder_distance(mavlink_channel_t chan);
|
||||
|
||||
// Log.cpp
|
||||
|
@ -123,13 +123,6 @@ void Rover::update_wheel_encoder()
|
||||
* posOffset is the XYZ body frame position of the wheel hub (m)
|
||||
*/
|
||||
EKF3.writeWheelOdom(delta_angle, delta_time, wheel_encoder_last_update_ms[i], g2.wheel_encoder.get_pos_offset(i), g2.wheel_encoder.get_wheel_radius(i));
|
||||
|
||||
// calculate rpm for reporting to GCS
|
||||
if (is_positive(delta_time)) {
|
||||
wheel_encoder_rpm[i] = (delta_angle / M_2PI) / (delta_time / 60.0f);
|
||||
} else {
|
||||
wheel_encoder_rpm[i] = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
// record system time update for next iteration
|
||||
|
Loading…
Reference in New Issue
Block a user