mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
AP_UAVCAN: add option bit for disabling Node Unhealthy check
This commit is contained in:
parent
3c87062f27
commit
4852ac332d
@ -122,7 +122,7 @@ const AP_Param::GroupInfo AP_UAVCAN::var_info[] = {
|
|||||||
// @Param: OPTION
|
// @Param: OPTION
|
||||||
// @DisplayName: UAVCAN options
|
// @DisplayName: UAVCAN options
|
||||||
// @Description: Option flags
|
// @Description: Option flags
|
||||||
// @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd
|
// @Bitmask: 0:ClearDNADatabase,1:IgnoreDNANodeConflicts,2:EnableCanfd,3:IgnoreDNANodeUnhealthy
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("OPTION", 5, AP_UAVCAN, _options, 0),
|
AP_GROUPINFO("OPTION", 5, AP_UAVCAN, _options, 0),
|
||||||
|
|
||||||
|
@ -202,6 +202,7 @@ public:
|
|||||||
DNA_CLEAR_DATABASE = (1U<<0),
|
DNA_CLEAR_DATABASE = (1U<<0),
|
||||||
DNA_IGNORE_DUPLICATE_NODE = (1U<<1),
|
DNA_IGNORE_DUPLICATE_NODE = (1U<<1),
|
||||||
CANFD_ENABLED = (1U<<2),
|
CANFD_ENABLED = (1U<<2),
|
||||||
|
DNA_IGNORE_UNHEALTHY_NODE = (1U<<3),
|
||||||
};
|
};
|
||||||
|
|
||||||
// check if a option is set
|
// check if a option is set
|
||||||
|
@ -475,8 +475,9 @@ void AP_UAVCAN_DNA_Server::handleNodeStatus(uint8_t node_id, const NodeStatusCb
|
|||||||
if (node_id > MAX_NODE_ID) {
|
if (node_id > MAX_NODE_ID) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (cb.msg->health != uavcan::protocol::NodeStatus::HEALTH_OK ||
|
if ((cb.msg->health != uavcan::protocol::NodeStatus::HEALTH_OK ||
|
||||||
cb.msg->mode != uavcan::protocol::NodeStatus::MODE_OPERATIONAL) {
|
cb.msg->mode != uavcan::protocol::NodeStatus::MODE_OPERATIONAL) &&
|
||||||
|
!_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {
|
||||||
//if node is not healthy or operational, clear resp health mask, and set fault_node_id
|
//if node is not healthy or operational, clear resp health mask, and set fault_node_id
|
||||||
fault_node_id = node_id;
|
fault_node_id = node_id;
|
||||||
server_state = NODE_STATUS_UNHEALTHY;
|
server_state = NODE_STATUS_UNHEALTHY;
|
||||||
@ -714,6 +715,10 @@ bool AP_UAVCAN_DNA_Server::prearm_check(char* fail_msg, uint8_t fail_msg_len) co
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
case NODE_STATUS_UNHEALTHY: {
|
case NODE_STATUS_UNHEALTHY: {
|
||||||
|
if (_ap_uavcan->option_is_set(AP_UAVCAN::Options::DNA_IGNORE_UNHEALTHY_NODE)) {
|
||||||
|
// ignore error
|
||||||
|
return true;
|
||||||
|
}
|
||||||
snprintf(fail_msg, fail_msg_len, "Node %d unhealthy!", fault_node_id);
|
snprintf(fail_msg, fail_msg_len, "Node %d unhealthy!", fault_node_id);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user