mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
8828659b33
commit
dd4d017717
|
@ -1354,6 +1354,7 @@ void AP_DroneCAN::handle_traffic_report(const CanardRxTransfer& transfer, const
|
|||
*/
|
||||
void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// log as CSRV message
|
||||
AP::logger().Write_ServoStatus(AP_HAL::micros64(),
|
||||
msg.actuator_id,
|
||||
|
@ -1362,6 +1363,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const
|
|||
msg.speed,
|
||||
msg.power_rating_pct,
|
||||
0, 0, 0, 0, 0, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if AP_DRONECAN_HIMARK_SERVO_SUPPORT
|
||||
|
@ -1370,6 +1372,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const
|
|||
*/
|
||||
void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// log as CSRV message
|
||||
AP::logger().Write_ServoStatus(AP_HAL::micros64(),
|
||||
msg.servo_id,
|
||||
|
@ -1383,12 +1386,14 @@ void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, cons
|
|||
msg.motor_temp*0.2-40,
|
||||
msg.pcb_temp*0.2-40,
|
||||
msg.error_status);
|
||||
#endif
|
||||
}
|
||||
#endif // AP_DRONECAN_HIMARK_SERVO_SUPPORT
|
||||
|
||||
#if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED
|
||||
void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP::logger().WriteStreaming(
|
||||
"CVOL",
|
||||
"TimeUS,Id,Pos,Cur,V,Pow,T",
|
||||
|
@ -1402,6 +1407,7 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer,
|
|||
msg.voltage * 0.2f,
|
||||
msg.motor_pwm * (100.0/255.0),
|
||||
int16_t(msg.motor_temperature) - 50);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -352,12 +352,14 @@ void AP_DroneCAN_DNA_Server::verify_nodes()
|
|||
return;
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
uint8_t log_count = AP::logger().get_log_start_count();
|
||||
if (log_count != last_logging_count) {
|
||||
last_logging_count = log_count;
|
||||
logged.clearall();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
//Check if we got acknowledgement from previous request
|
||||
//except for requests using our own node_id
|
||||
if (curr_verifying_node == self_node_id) {
|
||||
|
@ -438,6 +440,7 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co
|
|||
/*
|
||||
if we haven't logged this node then log it now
|
||||
*/
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (!logged.get(transfer.source_node_id) && AP::logger().logging_started()) {
|
||||
logged.set(transfer.source_node_id);
|
||||
uint64_t uid[2];
|
||||
|
@ -462,6 +465,7 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co
|
|||
rsp.software_version.minor,
|
||||
rsp.software_version.vcs_commit);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (isNodeIDOccupied(transfer.source_node_id)) {
|
||||
//if node_id already registered, just verify if Unique ID matches as well
|
||||
|
|
Loading…
Reference in New Issue