AP_DroneCAN: fixed Volz feedback build

This commit is contained in:
Andrew Tridgell 2023-04-13 09:46:32 +10:00 committed by Tom Pittenger
parent 3a811b8f1e
commit 6fbd8df95b
2 changed files with 8 additions and 12 deletions

View File

@ -71,10 +71,6 @@ extern const AP_HAL::HAL& hal;
#define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0
#endif
#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
#include <com/volz/servo/ActuatorStatus.hpp>
#endif
#define debug_dronecan(level_debug, fmt, args...) do { AP::can().log_text(level_debug, "DroneCAN", fmt, ##args); } while (0)
// Translation of all messages from DroneCAN structures into AP structures is done
@ -1054,7 +1050,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const
}
#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
void AP_DroneCAN::handle_actuator_status_Volz(AP_DroneCAN* ap_dronecan, uint8_t node_id, const ActuatorStatusVolzCb &cb)
void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg)
{
AP::logger().WriteStreaming(
"CVOL",
@ -1063,12 +1059,12 @@ void AP_DroneCAN::handle_actuator_status_Volz(AP_DroneCAN* ap_dronecan, uint8_t
"F-00000",
"QBfffBh",
AP_HAL::native_micros64(),
cb.msg->actuator_id,
ToDeg(cb.msg->actual_position),
cb.msg->current * 0.025f,
cb.msg->voltage * 0.2f,
cb.msg->motor_pwm * (100.0/255.0),
int16_t(cb.msg->motor_temperature) - 50);
msg.actuator_id,
ToDeg(msg.actual_position),
msg.current * 0.025f,
msg.voltage * 0.2f,
msg.motor_pwm * (100.0/255.0),
int16_t(msg.motor_temperature) - 50);
}
#endif

View File

@ -320,7 +320,7 @@ private:
void handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg);
void handle_traffic_report(const CanardRxTransfer& transfer, const ardupilot_equipment_trafficmonitor_TrafficReport& msg);
void handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg);
void handle_actuator_status_Volz(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg);
void handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg);
void handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg);
static bool is_esc_data_index_valid(const uint8_t index);
void handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg);