Skip to content
This repository has been archived by the owner on Sep 23, 2024. It is now read-only.

Commit

Permalink
Fix all those bugs in the implementation.
Browse files Browse the repository at this point in the history
  • Loading branch information
aentinger committed Jan 29, 2024
1 parent 9a9b899 commit 42ef189
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 12 deletions.
4 changes: 2 additions & 2 deletions include/viper/Node.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,8 +82,8 @@ class Node : public rclcpp::Node

/************** code************/

static uint16_t constexpr setpoint_velocity_ID = 113;
cyphal::Publisher<zubax::primitive::real16::Vector31> setpoint_velocity_ID;
static uint16_t constexpr SETPOINT_VELOCITY_ID = 113;
cyphal::Publisher<zubax::primitive::real16::Vector31_1_0> _setpoint_velocity_pub;

static std::chrono::milliseconds constexpr CTRL_LOOP_RATE{10};
rclcpp::TimerBase::SharedPtr _ctrl_loop_timer;
Expand Down
14 changes: 4 additions & 10 deletions src/Node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,10 +81,9 @@ Node::Node()

_ctrl_loop_timer = create_wall_timer(CTRL_LOOP_RATE, [this]() { this->ctrl_loop(); });

_cyphal_demo_pub = _node_hdl.create_publisher<uavcan::primitive::real16::Integer8_1_0>(CYPHAL_DEMO_PORT_ID, 1*1000*1000UL);

setpoint_velocity_ID= _node_hdl.create_subscription<zubax::primitive::real16::Vector31>(setpoint_velocity_ID,1*1000*1000UL)
_cyphal_demo_pub = _node_hdl.create_publisher<uavcan::primitive::scalar::Integer8_1_0>(CYPHAL_DEMO_PORT_ID, 1*1000*1000UL);

_setpoint_velocity_pub = _node_hdl.create_publisher<zubax::primitive::real16::Vector31_1_0>(SETPOINT_VELOCITY_ID, 1*1000*1000UL);

RCLCPP_INFO(get_logger(), "%s init complete.", get_name());
}
Expand Down Expand Up @@ -225,13 +224,8 @@ void Node::ctrl_loop()
_cyphal_demo_pub->publish(demo_msg);
demo_cnt++;

setpoint_velocity_ID = _node_hdl.create_publisher<zubax::primitive::real16::Vector31>(setpoint_velocity_ID, 1*1000*1000UL)
float motor_values[4] = {100.0, 100.0, 100.0, 100.0};
zubax::primitive::real16::Vector31 const motor_msg{motor_values};
setpoint_velocity_ID->publish(motor_msg);



zubax::primitive::real16::Vector31_1_0 const motor_msg{100.0, 100.0, 100.0, 100.0};
_setpoint_velocity_pub->publish(motor_msg);
}

/**************************************************************************************
Expand Down

0 comments on commit 42ef189

Please sign in to comment.