change msg to interfaces

This commit is contained in:
NuoDaJia02
2025-10-23 17:42:54 +08:00
parent ece5a41a6d
commit d8b03d8ad1
18 changed files with 70 additions and 84 deletions

View File

@@ -11,11 +11,12 @@ find_package(sensor_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(message_filters REQUIRED)
find_package(interfaces REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/DistMsg.msg"
DEPENDENCIES sensor_msgs
)
#rosidl_generate_interfaces(${PROJECT_NAME}
# "msg/DistMsg.msg"
# DEPENDENCIES sensor_msgs
#)
include_directories(
include
${CMAKE_CURRENT_BINARY_DIR}
@@ -23,16 +24,14 @@ include_directories(
)
add_executable(dist_dev_node src/main.cpp src/dist_dev_node.cpp src/ks104.cpp)
add_dependencies(dist_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
#add_dependencies(dist_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
target_link_libraries(dist_dev_node
${PROJECT_NAME}__rosidl_typesupport_cpp
${PROJECT_NAME}__rosidl_typesupport_c
message_filters::message_filters
)
ament_target_dependencies(dist_dev_node rclcpp sensor_msgs)
ament_target_dependencies(dist_dev_node rclcpp sensor_msgs interfaces)
install(TARGETS dist_dev_node DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch})

View File

@@ -5,7 +5,7 @@
#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "dist_dev/msg/dist_msg.hpp"
#include "interfaces/msg/dist_msg.hpp"
using namespace std;
namespace dist_dev{
@@ -16,8 +16,8 @@ namespace dist_dev{
void pub_msg(const sensor_msgs::msg::PointCloud2& pc,const DistCfg& cfg);
void pub_msg(const DistCfg& cfg);
private:
rclcpp::Publisher<dist_dev::msg::DistMsg>::SharedPtr dist_pub;
std::shared_ptr<dist_dev::msg::DistMsg> dist_msg;
rclcpp::Publisher<interfaces::msg::DistMsg>::SharedPtr dist_pub;
std::shared_ptr<interfaces::msg::DistMsg> dist_msg;
};
}

View File

@@ -1,6 +1,6 @@
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include "dist_dev/msg/dist_msg.hpp"// 自定义消息头文件
#include "interfaces/msg/dist_msg.hpp"// 自定义消息头文件
#include "dist_dev/dist_cfg.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.hpp>
@@ -8,8 +8,8 @@
#include"dist_dev/dist_dev_node.hpp"
namespace dist_dev{
DistSub::DistSub() : Node("dist_dev_node") {
dist_msg= std::make_shared<dist_dev::msg::DistMsg>();
dist_pub = this->create_publisher<dist_dev::msg::DistMsg>("/dist_msg", 10);
dist_msg= std::make_shared<interfaces::msg::DistMsg>();
dist_pub = this->create_publisher<interfaces::msg::DistMsg>("/dist_msg", 10);
}
static long long pub_cnt=0;
void DistSub::pub_msg(const sensor_msgs::msg::PointCloud2& pc,const DistCfg& cfg){

View File

@@ -1,5 +1,5 @@
#include <rclcpp/rclcpp.hpp>
#include "dist_dev/msg/dist_msg.hpp"
#include "interfaces/msg/dist_msg.hpp"
#include "dist_dev/dist_cfg.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.hpp>

View File

@@ -4,7 +4,7 @@
#include <cstdint>
#include <algorithm>
constexpr int NUM_SLAVES = 8; //定义电机数量
constexpr int NUM_SLAVES = 6; //定义电机数量
//运行模式
enum class OpMode : int8_t {

View File

@@ -287,7 +287,7 @@ void cyclic_task()
// 读取从站状态字、当前位置、速度、扭矩、运行模式
for (int i = 0; i < NUM_SLAVES; ++i)
{
if (i == 4)
if (i == 2)
// if (false)
{
uint16_t sw = EC_READ_U16(domain1_pd + zer_offsets[i].status_word);
@@ -671,12 +671,12 @@ bool start()
int position = i+1;
if (i > 3)
if (i > 1)
{
position = i+2;
}
if (i == 4)
if (i == 2)
{
sc[i] = ecrt_master_slave_config(master, 0, position, ZER_VID_PID);
if (!sc[i])
@@ -715,12 +715,12 @@ bool start()
int position = i+1;
if (i > 3)
if (i > 1)
{
position = i+2;
}
if (i == 4)
if (i == 2)
{
// ---- CSP/CSV/CST PDO ----
const size_t N = sizeof(zer_domain1_regs)/sizeof(zer_domain1_regs[0]);

View File

@@ -199,29 +199,23 @@ private:
switch (idx)
{
case 0:
idx = 3;
idx = 2;
break;
case 1:
idx = 4;
idx = 3;
break;
case 2:
idx = 0;
break;
case 3:
idx = 2;
break;
case 4:
idx = 1;
break;
case 5:
idx = 7;
break;
case 6:
idx = 6;
break;
case 7:
case 4:
idx = 5;
break;
case 5:
idx = 4;
break;
default:
break;
}

View File

@@ -119,29 +119,23 @@ void mc_get_state(int idx, uint16_t &status, int32_t &pos, int32_t &vel, int16_t
switch (idx)
{
case 0:
idx = 3;
idx = 2;
break;
case 1:
idx = 4;
idx = 3;
break;
case 2:
idx = 0;
break;
case 3:
idx = 2;
break;
case 4:
idx = 1;
break;
case 5:
idx = 7;
break;
case 6:
idx = 6;
break;
case 7:
case 4:
idx = 5;
break;
case 5:
idx = 4;
break;
default:
break;
}

View File

@@ -12,11 +12,12 @@ find_package(rclcpp REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(message_filters REQUIRED)
find_package(realsense2_camera_msgs REQUIRED)
find_package(interfaces REQUIRED)
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/ImgMsg.msg"
DEPENDENCIES sensor_msgs
)
#rosidl_generate_interfaces(${PROJECT_NAME}
# "msg/ImgMsg.msg"
# DEPENDENCIES sensor_msgs
#)
include_directories(
include
${CMAKE_CURRENT_BINARY_DIR}
@@ -24,16 +25,14 @@ include_directories(
)
add_executable(img_dev_node src/main.cpp src/img_dev_node.cpp)
add_dependencies(img_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
#add_dependencies(img_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
target_link_libraries(img_dev_node
${PROJECT_NAME}__rosidl_typesupport_cpp
${PROJECT_NAME}__rosidl_typesupport_c
message_filters::message_filters
)
ament_target_dependencies(img_dev_node rclcpp sensor_msgs realsense2_camera_msgs)
ament_target_dependencies(img_dev_node rclcpp sensor_msgs realsense2_camera_msgs interfaces)
install(TARGETS img_dev_node DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch})

View File

@@ -5,7 +5,7 @@
#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "img_dev/msg/img_msg.hpp"
#include "interfaces/msg/img_msg.hpp"
using namespace std;
namespace img_dev{
@@ -14,7 +14,7 @@ namespace img_dev{
ImageSubscriber() ;
void pub_msg(const sensor_msgs::msg::Image& c_img,const sensor_msgs::msg::Image& d_img,const ImgCfg& cfg);
private:
rclcpp::Publisher<img_dev::msg::ImgMsg>::SharedPtr img_pub;
std::shared_ptr<img_dev::msg::ImgMsg> img_msg;
rclcpp::Publisher<interfaces::msg::ImgMsg>::SharedPtr img_pub;
std::shared_ptr<interfaces::msg::ImgMsg> img_msg;
};
}

View File

@@ -1,6 +1,6 @@
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include "img_dev/msg/img_msg.hpp"// 自定义消息头文件
#include "interfaces/msg/img_msg.hpp"// 自定义消息头文件
#include "img_dev/img_cfg.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.hpp>
@@ -8,8 +8,8 @@
#include"img_dev/img_dev_node.hpp"
namespace img_dev{
ImageSubscriber::ImageSubscriber() : Node("image_subscriber") {
img_msg= std::make_shared<img_dev::msg::ImgMsg>();
img_pub = this->create_publisher<img_dev::msg::ImgMsg>("/img_msg", 10);
img_msg= std::make_shared<interfaces::msg::ImgMsg>();
img_pub = this->create_publisher<interfaces::msg::ImgMsg>("/img_msg", 10);
}
static long long pub_cnt=0;
void ImageSubscriber::pub_msg(const sensor_msgs::msg::Image& c_img,const sensor_msgs::msg::Image& d_img,const ImgCfg& cfg){

View File

@@ -1,7 +1,7 @@
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include "img_dev/msg/img_msg.hpp"
#include "interfaces/msg/img_msg.hpp"
#include "img_dev/img_cfg.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.hpp>

View File

@@ -12,6 +12,7 @@ find_package(std_msgs REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(message_filters REQUIRED)
find_package(interfaces REQUIRED)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
@@ -23,10 +24,10 @@ if(BUILD_TESTING)
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
rosidl_generate_interfaces(${PROJECT_NAME}
"msg/InputMsg.msg"
DEPENDENCIES sensor_msgs
)
#rosidl_generate_interfaces(${PROJECT_NAME}
# "msg/InputMsg.msg"
# DEPENDENCIES sensor_msgs
#)
include_directories(
include
${CMAKE_CURRENT_BINARY_DIR}
@@ -34,16 +35,14 @@ include_directories(
)
add_executable(input_dev_node src/main.cpp src/input_dev_node.cpp src/key_map.cpp)
add_dependencies(input_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
#add_dependencies(input_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
target_link_libraries(input_dev_node
${PROJECT_NAME}__rosidl_typesupport_cpp
${PROJECT_NAME}__rosidl_typesupport_c
message_filters::message_filters
)
ament_target_dependencies(input_dev_node rclcpp sensor_msgs)
ament_target_dependencies(input_dev_node rclcpp sensor_msgs interfaces)
install(TARGETS input_dev_node DESTINATION lib/${PROJECT_NAME})
install(DIRECTORY msg/ DESTINATION share/${PROJECT_NAME})
install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch)

View File

@@ -4,7 +4,7 @@
#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "message_filters/sync_policies/approximate_time.hpp"
#include "input_dev/msg/input_msg.hpp"
#include "interfaces/msg/input_msg.hpp"
using namespace std;
namespace input_dev{
@@ -15,8 +15,8 @@ namespace input_dev{
void pub_msg(const int key,const InputCfg& cfg);
void pub_msg(const int key,const float val,const InputCfg& cfg);
private:
rclcpp::Publisher<input_dev::msg::InputMsg>::SharedPtr input_pub;
std::shared_ptr<input_dev::msg::InputMsg> input_msg;
rclcpp::Publisher<interfaces::msg::InputMsg>::SharedPtr input_pub;
std::shared_ptr<interfaces::msg::InputMsg> input_msg;
};
}

View File

@@ -1,5 +1,5 @@
#include <rclcpp/rclcpp.hpp>
#include "input_dev/msg/input_msg.hpp"// 自定义消息头文件
#include "interfaces/msg/input_msg.hpp"// 自定义消息头文件
#include "input_dev/input_cfg.hpp"
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.hpp>
@@ -7,8 +7,8 @@
#include"input_dev/input_dev_node.hpp"
namespace input_dev{
InputSub::InputSub() : Node("InputSub") {
input_msg= std::make_shared<input_dev::msg::InputMsg>();
input_pub = this->create_publisher<input_dev::msg::InputMsg>("/input_msg", 10);
input_msg= std::make_shared<interfaces::msg::InputMsg>();
input_pub = this->create_publisher<interfaces::msg::InputMsg>("/input_msg", 10);
}
static long long pub_cnt=0;
void InputSub::pub_msg(const int key,const float val,const InputCfg& cfg){

View File

@@ -1,5 +1,5 @@
#include <rclcpp/rclcpp.hpp>
#include "input_dev/msg/input_msg.hpp"
#include "interfaces/msg/input_msg.hpp"
#include "std_msgs/msg/string.hpp"
#include "input_dev/input_cfg.hpp"
#include <message_filters/subscriber.h>

View File

@@ -10,13 +10,14 @@ find_package(ament_cmake REQUIRED)
find_package(std_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(interfaces REQUIRED)
#rosidl_generate_interfaces(${PROJECT_NAME} "msg/MotorCmd.msg")
rosidl_generate_interfaces(${PROJECT_NAME} "msg/MotorCmd.msg" "msg/MotorPos.msg")
#rosidl_generate_interfaces(${PROJECT_NAME} "msg/MotorCmd.msg" "msg/MotorPos.msg")
include_directories(include ${CMAKE_CURRENT_BINARY_DIR}/rosidl_generator_cpp)
add_executable(motor_dev_node src/main.cpp src/rs485_driver.cpp)
add_dependencies(motor_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
target_link_libraries(motor_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp )
ament_target_dependencies(motor_dev_node rclcpp std_msgs)
#add_dependencies(motor_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp)
#target_link_libraries(motor_dev_node ${PROJECT_NAME}__rosidl_typesupport_cpp )
ament_target_dependencies(motor_dev_node rclcpp std_msgs interfaces )
install(TARGETS motor_dev_node DESTINATION lib/${PROJECT_NAME})
if(BUILD_TESTING)

View File

@@ -1,7 +1,7 @@
#include"rclcpp/rclcpp.hpp"
#include"motor_dev/rs485_driver.hpp"
#include"motor_dev/msg/motor_cmd.hpp"
#include"motor_dev/msg/motor_pos.hpp"
#include"interfaces/msg/motor_cmd.hpp"
#include"interfaces/msg/motor_pos.hpp"
using namespace motor_dev;
RS485Driver rs485_driver_;
@@ -29,7 +29,7 @@ int main(int argc,char* argv[]){
//rs485_driver_.mt_set_pos(1,-5);
//init
/////rs485_driver_.bm_set_mode(1,3);//位置模式
auto rs485_sub_=node->create_subscription<motor_dev::msg::MotorCmd>("/motor_cmd",10,[](const motor_dev::msg::MotorCmd::SharedPtr msg){
auto rs485_sub_=node->create_subscription<interfaces::msg::MotorCmd>("/motor_cmd",10,[](const interfaces::msg::MotorCmd::SharedPtr msg){
///
if (msg->target == "rs485") {
if(msg->type=="bm"){
@@ -51,11 +51,11 @@ int main(int argc,char* argv[]){
//TODO
}
});
auto motor_pub=node->create_publisher<motor_dev::msg::MotorPos>("/motor_pos",10);
auto motor_pub=node->create_publisher<interfaces::msg::MotorPos>("/motor_pos",10);
//读取电机位置
rclcpp::TimerBase::SharedPtr timer_=node->create_wall_timer(std::chrono::milliseconds(2000), [=]() {
static int pub_cnt=0;
motor_dev::msg::MotorPos motor_pos;
interfaces::msg::MotorPos motor_pos;
float angle1=rs485_driver_.bm_get_pos(1);
float angle2=rs485_driver_.bm_get_pos(2);
///printf("bm cur angle:%.1f\n",angle);