Skip to content

Commit

Permalink
AP_ESC_Telem: Use const when applicable
Browse files Browse the repository at this point in the history
  • Loading branch information
amilcarlucas authored and andyp1per committed May 7, 2021
1 parent 8880e34 commit 2170e9a
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 9 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.cpp
Expand Up @@ -256,7 +256,7 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)

// record an update to the telemetry data together with timestamp
// this should be called by backends when new telemetry values are available
void AP_ESC_Telem::update_telem_data(uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, uint16_t data_mask)
void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask)
{
// rpm and telemetry data are not protected by a semaphore even though updated from different threads
// all data is per-ESC and only written from the update thread and read by the user thread
Expand Down Expand Up @@ -294,7 +294,7 @@ void AP_ESC_Telem::update_telem_data(uint8_t esc_index, const AP_ESC_Telem_Backe

// record an update to the RPM together with timestamp, this allows the notch values to be slewed
// this should be called by backends when new telemetry values are available
void AP_ESC_Telem::update_rpm(uint8_t esc_index, uint16_t new_rpm, float error_rate)
void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate)
{
if (esc_index > ESC_TELEM_MAX_ESCS) {
return;
Expand Down Expand Up @@ -335,7 +335,7 @@ void AP_ESC_Telem::update()
// rpm is eRPM (rpm * 100)
// voltage is in Volt
// current is in Ampere
// temperature is in centi-degrees Celsius
// esc_temp is in centi-degrees Celsius
// current_tot is in mili-Ampere hours
// motor_temp is in centi-degrees Celsius
// error_rate is in percentage
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ESC_Telem/AP_ESC_Telem.h
Expand Up @@ -68,9 +68,9 @@ class AP_ESC_Telem {

private:
// callback to update the rpm in the frontend, should be called by the driver when new data is available
void update_rpm(uint8_t esc_index, uint16_t new_rpm, float error_rate);
void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate);
// callback to update the data in the frontend, should be called by the driver when new data is available
void update_telem_data(uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, uint16_t data_mask);
void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask);

// rpm data
volatile AP_ESC_Telem_Backend::RpmData _rpm_data[ESC_TELEM_MAX_ESCS];
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp
Expand Up @@ -31,12 +31,12 @@ AP_ESC_Telem_Backend::AP_ESC_Telem_Backend() {
}

// callback to update the rpm in the frontend, should be called by the driver when new data is available
void AP_ESC_Telem_Backend::update_rpm(uint8_t esc_index, uint16_t new_rpm, float error_rate) {
void AP_ESC_Telem_Backend::update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate) {
_frontend->update_rpm(esc_index, new_rpm, error_rate);
}

// callback to update the data in the frontend, should be called by the driver when new data is available
void AP_ESC_Telem_Backend::update_telem_data(uint8_t esc_index, const TelemetryData& new_data, uint16_t data_present_mask) {
void AP_ESC_Telem_Backend::update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask) {
_frontend->update_telem_data(esc_index, new_data, data_present_mask);
}

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h
Expand Up @@ -51,10 +51,10 @@ class AP_ESC_Telem_Backend {

protected:
// callback to update the rpm in the frontend, should be called by the driver when new data is available
void update_rpm(uint8_t esc_index, uint16_t new_rpm, float error_rate = 0.0f);
void update_rpm(const uint8_t esc_index, const uint16_t new_rpm, const float error_rate = 0.0f);

// callback to update the data in the frontend, should be called by the driver when new data is available
void update_telem_data(uint8_t esc_index, const TelemetryData& new_data, uint16_t data_present_mask);
void update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask);

private:
AP_ESC_Telem* _frontend;
Expand Down

0 comments on commit 2170e9a

Please sign in to comment.