mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_DroneCAN: fixed Volz feedback build
This commit is contained in:
parent
3a811b8f1e
commit
6fbd8df95b
@ -71,10 +71,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
#define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0
|
#define AP_DRONECAN_VOLZ_FEEDBACK_ENABLED 0
|
||||||
#endif
|
#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)
|
#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
|
// 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
|
#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(
|
AP::logger().WriteStreaming(
|
||||||
"CVOL",
|
"CVOL",
|
||||||
@ -1063,12 +1059,12 @@ void AP_DroneCAN::handle_actuator_status_Volz(AP_DroneCAN* ap_dronecan, uint8_t
|
|||||||
"F-00000",
|
"F-00000",
|
||||||
"QBfffBh",
|
"QBfffBh",
|
||||||
AP_HAL::native_micros64(),
|
AP_HAL::native_micros64(),
|
||||||
cb.msg->actuator_id,
|
msg.actuator_id,
|
||||||
ToDeg(cb.msg->actual_position),
|
ToDeg(msg.actual_position),
|
||||||
cb.msg->current * 0.025f,
|
msg.current * 0.025f,
|
||||||
cb.msg->voltage * 0.2f,
|
msg.voltage * 0.2f,
|
||||||
cb.msg->motor_pwm * (100.0/255.0),
|
msg.motor_pwm * (100.0/255.0),
|
||||||
int16_t(cb.msg->motor_temperature) - 50);
|
int16_t(msg.motor_temperature) - 50);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -320,7 +320,7 @@ private:
|
|||||||
void handle_button(const CanardRxTransfer& transfer, const ardupilot_indication_Button& msg);
|
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_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(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);
|
void handle_ESC_status(const CanardRxTransfer& transfer, const uavcan_equipment_esc_Status& msg);
|
||||||
static bool is_esc_data_index_valid(const uint8_t index);
|
static bool is_esc_data_index_valid(const uint8_t index);
|
||||||
void handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg);
|
void handle_debug(const CanardRxTransfer& transfer, const uavcan_protocol_debug_LogMessage& msg);
|
||||||
|
Loading…
Reference in New Issue
Block a user