3.1写一个简单的ROS通讯库

本文档隶属于工程机械臂末端柔顺控制(Ros+Gazebo仿真实现)

0 为什么要写这玩意儿?

要实现末端柔顺控制至少得先具备检测末端力数据以及发送控制指令给机器人的功能,力传感器和机器人位置控制器我们已经在如何给Gazebo中的仿真机械臂添加一个力传感器?中实现了,接下来就要写一个上位机程序来采集力传感器数据以及给机械臂发送控制指令。

1 工程目录

工程目录如下:

RosCommunication
    include(存放头文件)
        RosCommunication.h
    lib(存放生成的库文件)
    src(存放源文件)
        RosCommunication.cpp
        test_RosCommunication.cpp
    bin(存放可执行文件)
    build(存放编译过程中的中间文件:不用管)
    CMakeLists.txt

本文虽使用了ROS的部分官方头文件,但并未按照ROS模式的工程目录进行编写。

2 头文件RosCommunication.h

代码如下:

#pragma once
/*  This file name is RosCommunication.h  */
#include "ros/ros.h"
#include "sensor_msgs/JointState.h"
#include "geometry_msgs/WrenchStamped.h"
#include "std_msgs/Float64MultiArray.h"
#include <string>

/* This is a dedicated ROS communication class. There are three methods in this class  */
class RosCommunication
{
public:
    RosCommunication(std::string JointCommandTopic, std::string JointStateTopic, std::string FtSensorTopic, ros::NodeHandle &nh);
    RosCommunication() = delete;
    RosCommunication(const RosCommunication &) = delete;
    RosCommunication &operator=(const RosCommunication &) = delete;

public:
    //Send joint control commands(JointArray) to the JointCommandTopic
    void SetJointPosition(const std_msgs::Float64MultiArray &JointArray);

    //Get a joint state message from the JointStateTopic
    sensor_msgs::JointState::ConstPtr GetJointState();

    //Get a force messag
  • 3
    点赞
  • 13
    收藏
    觉得还不错? 一键收藏
  • 2
    评论
评论 2
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值