code update

This commit is contained in:
NuoDaJia02
2025-10-29 17:00:27 +08:00
parent 38a4c4a193
commit 67615b7e9d
12 changed files with 134 additions and 77 deletions

View File

@@ -11,6 +11,7 @@ find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(motor_dev REQUIRED)
find_package(interfaces REQUIRED)
find_package(std_msgs REQUIRED)
add_executable(motor_test src/main.cpp)
ament_target_dependencies(motor_test rclcpp motor_dev interfaces)

View File

@@ -2,6 +2,7 @@
#include <memory>
#include "rclcpp/rclcpp.hpp"
#include "interfaces/msg/motor_cmd.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
@@ -14,15 +15,18 @@ public:
: Node("motor_test_node")
{
publisher_ = this->create_publisher<MotorCmd>("/motor_cmd", 10);
//publisher_ = this->create_publisher<std_msgs::msg::String>("/led_cmd", 10);
timer_ = this->create_wall_timer(100ms, std::bind(&MotorCmdPublisher::timer_callback, this));
timer_ = this->create_wall_timer(5000ms, std::bind(&MotorCmdPublisher::timer_callback, this));
}
private:
int angle1=9999;
int angle2=6666;
int xcnt=0;
void timer_callback()
{
#if 1
auto message = MotorCmd();
message.target = "rs485";
@@ -44,14 +48,25 @@ private:
message.motor_angle.push_back((float)angle1);
message.motor_angle.push_back((float)angle2);
publisher_->publish(message);
RCLCPP_INFO(this->get_logger(), "Published MotorCmd message:%d,%d",angle1,angle2);
timer_->cancel();
#endif
#if 0
auto message=std_msgs::msg::String();
xcnt+=1;
if(xcnt%2==0)
message.data="green,10";
else
message.data="blue,10";
publisher_->publish(message);
RCLCPP_INFO(this->get_logger(), "Published LedCmd message:%s",message.data.c_str());
#endif
//timer_->cancel();
}
int idx=0;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<MotorCmd>::SharedPtr publisher_;
//rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
};
int main(int argc, char * argv[])