Skip to content

Commit

Permalink
fixed more merge errors
Browse files Browse the repository at this point in the history
  • Loading branch information
ErikParkerrr committed Jan 10, 2025
1 parent 67f9747 commit 4069fad
Showing 1 changed file with 1 addition and 6 deletions.
7 changes: 1 addition & 6 deletions odrive_node/src/odrive_can_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,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 @@ -206,11 +206,6 @@ void ODriveCanNode::service_clear_errors_callback(const std::shared_ptr<Empty::R
(void)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();
}

void ODriveCanNode::request_state_callback() {
uint32_t axis_state;
{
Expand Down

0 comments on commit 4069fad

Please sign in to comment.