Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions odrive_node/src/odrive_can_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ ODriveCanNode::ODriveCanNode(const std::string& node_name) : rclcpp::Node(node_n

void ODriveCanNode::deinit() {
if (axis_idle_on_shutdown_) {
struct can_frame frame;
struct can_frame frame = {};
frame.can_id = node_id_ << 5 | CmdId::kSetAxisState;
write_le<uint32_t>(ODriveAxisState::AXIS_STATE_IDLE, frame.data);
frame.can_dlc = 4;
Expand Down Expand Up @@ -221,7 +221,7 @@ void ODriveCanNode::service_callback(const std::shared_ptr<AxisState::Request> r
response->procedure_result = ctrl_stat_.procedure_result;
}

void ODriveCanNode::service_clear_errors_callback(const std::shared_ptr<Empty::Request> request, std::shared_ptr<Empty::Response> response) {
void ODriveCanNode::service_clear_errors_callback(const std::shared_ptr<Empty::Request> /*request*/, std::shared_ptr<Empty::Response> /*response*/) {
RCLCPP_INFO(rclcpp::Node::get_logger(), "clearing errors");
srv_clear_errors_evt_.set();
}
Expand Down Expand Up @@ -251,7 +251,7 @@ void ODriveCanNode::request_state_callback() {
}

void ODriveCanNode::request_clear_errors_callback() {
struct can_frame frame;
struct can_frame frame = {};
frame.can_id = node_id_ << 5 | CmdId::kClearErrors;
write_le<uint8_t>(0, frame.data);
frame.can_dlc = 1;
Expand Down
Loading