ROS turtlebot_follower :让机器人跟随我们移动

2023-11-16

ROS turtlebot_follower 学习
首先在catkin_ws/src目录下载源码,地址:https://github.com/turtlebot/turtlebot_apps.git
了解代码见注释(其中有些地方我也不是很明白)
follower.cpp

#include <ros/ros.h>
#include <pluginlib/class_list_macros.h>
#include <nodelet/nodelet.h>
#include <geometry_msgs/Twist.h>
#include <sensor_msgs/Image.h>
#include <visualization_msgs/Marker.h>
#include <turtlebot_msgs/SetFollowState.h>

#include "dynamic_reconfigure/server.h"
#include "turtlebot_follower/FollowerConfig.h"

#include <depth_image_proc/depth_traits.h>


namespace turtlebot_follower
{

//* The turtlebot follower nodelet.
/**
 * The turtlebot follower nodelet. Subscribes to point clouds
 * from the 3dsensor, processes them, and publishes command vel
 * messages.
 */
class TurtlebotFollower : public nodelet::Nodelet
{
public:
  /*!
   * @brief The constructor for the follower.
   * Constructor for the follower.
   */
  TurtlebotFollower() : min_y_(0.1), max_y_(0.5),
                        min_x_(-0.2), max_x_(0.2),
                        max_z_(0.8), goal_z_(0.6),
                        z_scale_(1.0), x_scale_(5.0)
  {

  }

  ~TurtlebotFollower()
  {
    delete config_srv_;
  }

private:
  double min_y_; /**< The minimum y position of the points in the box. */
  double max_y_; /**< The maximum y position of the points in the box. */
  double min_x_; /**< The minimum x position of the points in the box. */
  double max_x_; /**< The maximum x position of the points in the box. */
  double max_z_; /**< The maximum z position of the points in the box. 框中 点的最大z位置,以上四个字段用来设置框的大小*/
  double goal_z_; /**< The distance away from the robot to hold the centroid 离机器人的距离,以保持质心*/
  double z_scale_; /**< The scaling factor for translational robot speed 移动机器人速度的缩放系数*/
  double x_scale_; /**< The scaling factor for rotational robot speed 旋转机器人速度的缩放系数*/
  bool   enabled_; /**< Enable/disable following; just prevents motor commands 启用/禁用追踪; 只是阻止电机命令,置为false后,机器人不会移动,/mobile_base/mobile_base_controller/cmd_vel topic 为空*/

  // Service for start/stop following
  ros::ServiceServer switch_srv_;

  // Dynamic reconfigure server 动态配置服务
  dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>* config_srv_;

  /*!
   * @brief OnInit method from node handle.
   * OnInit method from node handle. Sets up the parameters
   * and topics.
   * 初始化handle,参数,和话题
   */
  virtual void onInit()
  {
    ros::NodeHandle& nh = getNodeHandle();
    ros::NodeHandle& private_nh = getPrivateNodeHandle();
   //从参数服务器获取设置的参数(launch文件中设置数值)
    private_nh.getParam("min_y", min_y_);
    private_nh.getParam("max_y", max_y_);
    private_nh.getParam("min_x", min_x_);
    private_nh.getParam("max_x", max_x_);
    private_nh.getParam("max_z", max_z_);
    private_nh.getParam("goal_z", goal_z_);
    private_nh.getParam("z_scale", z_scale_);
    private_nh.getParam("x_scale", x_scale_);
    private_nh.getParam("enabled", enabled_);
    //设置机器人移动的话题(用于机器人移动):/mobile_base/mobile_base_controller/cmd_vel(换成你的机器人的移动topic)
    cmdpub_ = private_nh.advertise<geometry_msgs::Twist> ("/mobile_base/mobile_base_controller/cmd_vel", 1);
    
    markerpub_ = private_nh.advertise<visualization_msgs::Marker>("marker",1);
    bboxpub_ = private_nh.advertise<visualization_msgs::Marker>("bbox",1);
    sub_= nh.subscribe<sensor_msgs::Image>("depth/image_rect", 1, &TurtlebotFollower::imagecb, this);

    switch_srv_ = private_nh.advertiseService("change_state", &TurtlebotFollower::changeModeSrvCb, this);

    config_srv_ = new dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>(private_nh);
    dynamic_reconfigure::Server<turtlebot_follower::FollowerConfig>::CallbackType f =
        boost::bind(&TurtlebotFollower::reconfigure, this, _1, _2);
    config_srv_->setCallback(f);
  }

//设置默认值,详见catkin_ws/devel/include/turtlrbot_follower/FollowerConfig.h
  void reconfigure(turtlebot_follower::FollowerConfig &config, uint32_t level)
  {
    min_y_ = config.min_y;
    max_y_ = config.max_y;
    min_x_ = config.min_x;
    max_x_ = config.max_x;
    max_z_ = config.max_z;
    goal_z_ = config.goal_z;
    z_scale_ = config.z_scale;
    x_scale_ = config.x_scale;
  }

  /*!
   * @brief Callback for point clouds.
   * Callback for depth images. It finds the centroid
   * of the points in a box in the center of the image. 
   * 它找到图像中心框中的点的质心
   * Publishes cmd_vel messages with the goal from the image.
   * 发布图像中目标的cmd_vel 消息
   * @param cloud The point cloud message.
   * 参数:点云的消息
   */
  void imagecb(const sensor_msgs::ImageConstPtr& depth_msg)
  {

    // Precompute the sin function for each row and column wangchao预计算每行每列的正弦函数
    uint32_t image_width = depth_msg->width;
    ROS_INFO_THROTTLE(1, "image_width=%d", image_width);
    float x_radians_per_pixel = 60.0/57.0/image_width;//每个像素的弧度
    float sin_pixel_x[image_width];
    for (int x = 0; x < image_width; ++x) {
      //求出正弦值
      sin_pixel_x[x] = sin((x - image_width/ 2.0)  * x_radians_per_pixel);
    }

    uint32_t image_height = depth_msg->height;
    float y_radians_per_pixel = 45.0/57.0/image_width;
    float sin_pixel_y[image_height];
    for (int y = 0; y < image_height; ++y) {
      // Sign opposite x for y up values 
      sin_pixel_y[y] = sin((image_height/ 2.0 - y)  * y_radians_per_pixel);
    }

    //X,Y,Z of the centroid 质心的xyz
    float x = 0.0;
    float y = 0.0;
    float z = 1e6;
    //Number of points observed 观察的点数
    unsigned int n = 0;

    //Iterate through all the points in the region and find the average of the position 迭代通过该区域的所有点,找到位置的平均值
    const float* depth_row = reinterpret_cast<const float*>(&depth_msg->data[0]);
    int row_step = depth_msg->step / sizeof(float);
    for (int v = 0; v < (int)depth_msg->height; ++v, depth_row += row_step)
    {
     for (int u = 0; u < (int)depth_msg->width; ++u)
     {
       float depth = depth_image_proc::DepthTraits<float>::toMeters(depth_row[u]);
       if (!depth_image_proc::DepthTraits<float>::valid(depth) || depth > max_z_) continue;//不是有效的深度值或者深度超出max_z_
       float y_val = sin_pixel_y[v] * depth;
       float x_val = sin_pixel_x[u] * depth;
       if ( y_val > min_y_ && y_val < max_y_ &&
            x_val > min_x_ && x_val < max_x_)
       {
         x += x_val;
         y += y_val;
         z = std::min(z, depth); //approximate depth as forward.
         n++;
       }
     }
    }

    //If there are points, find the centroid and calculate the command goal.
    //If there are no points, simply publish a stop goal.
    //如果有点,找到质心并计算命令目标。如果没有点,只需发布停止消息。
    ROS_INFO_THROTTLE(1, " n ==%d",n);
    if (n>4000)
    {
      x /= n;
      y /= n;
      if(z > max_z_){
        ROS_INFO_THROTTLE(1, "Centroid too far away %f, stopping the robot\n", z);
        if (enabled_)
        {
          cmdpub_.publish(geometry_msgs::TwistPtr(new geometry_msgs::Twist()));
        }
        return;
      }

      ROS_INFO_THROTTLE(1, "Centroid at %f %f %f with %d points", x, y, z, n);
      publishMarker(x, y, z);

      if (enabled_)
      {
        geometry_msgs::TwistPtr cmd(new geometry_msgs::Twist());
        cmd->linear.x = (z - goal_z_) * z_scale_;
        cmd->angular.z = -x * x_scale_;
        cmdpub_.publish(cmd);
      }
    }
    else
    {

      ROS_INFO_THROTTLE(1, "Not enough points(%d) detected, stopping the robot", n);
      publishMarker(x, y, z);

      if (enabled_)
      {

        cmdpub_.publish(geometry_msgs::TwistPtr(new geometry_msgs::Twist()));
      }
    }

    publishBbox();
  }

  bool changeModeSrvCb(turtlebot_msgs::SetFollowState::Request& request,
                       turtlebot_msgs::SetFollowState::Response& response)
  {
    if ((enabled_ == true) && (request.state == request.STOPPED))
    {
      ROS_INFO("Change mode service request: following stopped");
      cmdpub_.publish(geometry_msgs::TwistPtr(new geometry_msgs::Twist()));
      enabled_ = false;
    }
    else if ((enabled_ == false) && (request.state == request.FOLLOW))
    {
      ROS_INFO("Change mode service request: following (re)started");
      enabled_ = true;
    }

    response.result = response.OK;
    return true;
  }
 //画一个圆点,这个圆点代表质心
  void publishMarker(double x,double y,double z)
  {
    visualization_msgs::Marker marker;
    marker.header.frame_id = "/camera_rgb_optical_frame";
    marker.header.stamp = ros::Time();
    marker.ns = "my_namespace";
    marker.id = 0;
    marker.type = visualization_msgs::Marker::SPHERE;
    marker.action = visualization_msgs::Marker::ADD;
    marker.pose.position.x = x;
    marker.pose.position.y = y;
    marker.pose.position.z = z;
    marker.pose.orientation.x = 0.0;
    marker.pose.orientation.y = 0.0;
    marker.pose.orientation.z = 0.0;
    marker.pose.orientation.w = 1.0;
    marker.scale.x = 0.1;
    marker.scale.y = 0.1;
    marker.scale.z = 0.1;
    marker.color.a = 1.0;
    marker.color.r = 1.0;
    marker.color.g = 0.0;
    marker.color.b = 0.0;
    //only if using a MESH_RESOURCE marker type:
    markerpub_.publish( marker );
  }
 //画一个立方体,这个立方体代表感兴趣区域(RIO)
  void publishBbox()
  {
    double x = (min_x_ + max_x_)/2;
    double y = (min_y_ + max_y_)/2;
    double z = (0 + max_z_)/2;

    double scale_x = (max_x_ - x)*2;
    double scale_y = (max_y_ - y)*2;
    double scale_z = (max_z_ - z)*2;

    visualization_msgs::Marker marker;
    marker.header.frame_id = "/camera_rgb_optical_frame";
    marker.header.stamp = ros::Time();
    marker.ns = "my_namespace";
    marker.id = 1;
    marker.type = visualization_msgs::Marker::CUBE;
    marker.action = visualization_msgs::Marker::ADD;
    //设置标记物姿态
    marker.pose.position.x = x;
    marker.pose.position.y = -y;
    marker.pose.position.z = z;
    marker.pose.orientation.x = 0.0;
    marker.pose.orientation.y = 0.0;
    marker.pose.orientation.z = 0.0;
    marker.pose.orientation.w = 1.0;
    //设置标记物的尺寸大小
    marker.scale.x = scale_x;
    marker.scale.y = scale_y;
    marker.scale.z = scale_z;
    
    marker.color.a = 0.5;
    marker.color.r = 0.0;
    marker.color.g = 1.0;
    marker.color.b = 0.0;
    //only if using a MESH_RESOURCE marker type:
    bboxpub_.publish( marker );
  }

  ros::Subscriber sub_;
  ros::Publisher cmdpub_;
  ros::Publisher markerpub_;
  ros::Publisher bboxpub_;
};

PLUGINLIB_DECLARE_CLASS(turtlebot_follower, TurtlebotFollower, turtlebot_follower::TurtlebotFollower, nodelet::Nodelet);

}

接下来看launch文件follower.launch
建议在修改前,将原先的代码注释掉,不要删掉。

<!--
  The turtlebot people (or whatever) follower nodelet.
 -->
<launch>
  <arg name="simulation" default="false"/>
  <group unless="$(arg simulation)"> <!-- Real robot -->
    <include file="$(find turtlebot_follower)/launch/includes/velocity_smoother.launch.xml">
      <arg name="nodelet_manager"  value="/mobile_base_nodelet_manager"/>
      <arg name="navigation_topic" value="/cmd_vel_mux/input/navi"/>
    </include>
    <!--modify by 2016.11.07 启动我的机器人和摄像头,这里更换成你的机器人的启动文件和摄像头启动文件-->
    <include file="$(find handsfree_hw)/launch/handsfree_hw.launch">
    </include>
    <include file="$(find handsfree_bringup)/launch/xtion_fake_laser_openni2.launch">
    </include>

   
   <!-- 将原先的注释掉<include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
      <arg name="rgb_processing"                  value="true"/> 
      <arg name="depth_processing"                value="true"/>
      <arg name="depth_registered_processing"     value="false"/>
      <arg name="depth_registration"              value="false"/>
      <arg name="disparity_processing"            value="false"/>
      <arg name="disparity_registered_processing" value="false"/>
      <arg name="scan_processing"                 value="false"/>
    </include>-->
  <!--modify end -->
  </group>
  <group if="$(arg simulation)">
    <!-- Load nodelet manager for compatibility -->
    <node pkg="nodelet" type="nodelet" ns="camera" name="camera_nodelet_manager" args="manager"/>

    <include file="$(find turtlebot_follower)/launch/includes/velocity_smoother.launch.xml">
      <arg name="nodelet_manager"  value="camera/camera_nodelet_manager"/>
      <arg name="navigation_topic" value="cmd_vel_mux/input/navi"/>
    </include>
  </group>

  <param name="camera/rgb/image_color/compressed/jpeg_quality" value="22"/>

  <!-- Make a slower camera feed available; only required if we use android client -->
  <node pkg="topic_tools" type="throttle" name="camera_throttle"
        args="messages camera/rgb/image_color/compressed 5"/>

  <include file="$(find turtlebot_follower)/launch/includes/safety_controller.launch.xml"/>

  <!--  Real robot: Load turtlebot follower into the 3d sensors nodelet manager to avoid pointcloud serializing -->
  <!--  Simulation: Load turtlebot follower into nodelet manager for compatibility -->
  <node pkg="nodelet" type="nodelet" name="turtlebot_follower"
        args="load turtlebot_follower/TurtlebotFollower camera/camera_nodelet_manager">
     <!--更换成你的机器人的移动topic,我的是/mobile_base/mobile_base_controller/cmd_vel-->
    <remap from="turtlebot_follower/cmd_vel" to="/mobile_base/mobile_base_controller/cmd_vel"/>
    <remap from="depth/points" to="camera/depth/points"/>
    <param name="enabled" value="true" />
    <!--<param name="x_scale" value="7.0" />-->
    <!--<param name="z_scale" value="2.0" />
    <param name="min_x" value="-0.35" />
    <param name="max_x" value="0.35" />
    <param name="min_y" value="0.1" />
    <param name="max_y" value="0.6" />
    <param name="max_z" value="1.2" />
    <param name="goal_z" value="0.6" />-->
    
    
    <!-- test  可以在此处调节参数-->
    <param name="x_scale" value="1.5"/>
    <param name="z_scale" value="1.0" />
    <param name="min_x" value="-0.35" />
    <param name="max_x" value="0.35" />
    <param name="min_y" value="0.1" />
    <param name="max_y" value="0.5" />
    <param name="max_z" value="1.5" />
    <param name="goal_z" value="0.6" />
  </node>
  <!-- Launch the script which will toggle turtlebot following on and off based on a joystick button. default: on -->
  <node name="switch" pkg="turtlebot_follower" type="switch.py"/>
 <!--modify  2016.11.07 在turtlebot_follower下新建follow.rviz文件,加载rviz,此时rviz内容为空-->
  <node name="rviz" pkg="rviz" type="rviz" args="-d $(find turtlebot_follower)/follow.rviz"/>
<!--modify end -->
</launch>

编译,运行follow.launch 会将机器人和摄像头,rviz都启动起来,只需要运行这一个launch就可以了。
rviz中添加两个marker,pointcloud,camera。如图:
这里写图片描述

这里写图片描述

topic与frame名称与代码中要保持一致。
添加完之后,rviz显示如图:
这里写图片描述
红点代表质心,绿框代表感兴趣区域
当红点在我们身上时,机器人会跟随我们运动,注意:走动时,我们的速度要慢一点,机器人的移动速度也要调慢一点。这里写图片描述
当感兴趣区域没有红点时,机器人停止跟随,直到出现红点。

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

ROS turtlebot_follower :让机器人跟随我们移动 的相关文章

  • ROS AsyncSpinner 的多线程行为

    我试图了解 ROS 中的 AsyncSpinner 是如何工作的 因为我可能有一些误解 你可以找到类似的问题here As seen here它的定义提到 异步旋转器 产生几个线程 可配置 将并行执行回调 同时不会阻塞执行该操作的线程 叫它
  • 提升客服效率!RPA机器人助力电商客服快速回复

    电商行业是一个快速发展的行业 随着互联网的普及和消费者对网购的需求增加 电商平台上的客服工作也变得越来越重要 面对各种问题影响了电商的发展 1 信息处理繁琐 客服人员需要处理大量的信息和数据 包括回复客户的咨询 处理退换货 解决投诉等 这些
  • 提升电商运营效率!微商易代理网站自动上架商品RPA机器人来了!

    在电商运营中 为了提高处理效率 节省人力成本 我们经常需要处理大量的重复性工作 比如商品的上架 物流的管理等等 然而 这些工作不仅耗时费力 而且容易出错 给电商运营带来了很大的困扰 为了解决这些问题 我们可以借助八爪鱼rpa这款强大的机器人
  • 【四旋翼飞行器】【模拟悬链机器人的动态】设计和控制由两个四旋翼飞行器推动的缆绳研究(Matlab代码实现)

    欢迎来到本博客 博主优势 博客内容尽量做到思维缜密 逻辑清晰 为了方便读者 座右铭 行百里者 半于九十 本文目录如下 目录 1 概述 2 运行结果 3 参考文献 4 Matlab代码实现
  • 不使用ros编译roscpp(使用g++)

    我正在尝试在不使用ROS其余部分的情况下编译roscpp 我只需要订阅一个节点 但该节点拥有使用旧版本ROS的节点 并且由于编译问题 我无法将我的程序与他的程序集成 我从git下载了源代码 https github com ros ros
  • 用RPA轻松获取亚马逊销售订单详细信息,提升业务效率!

    在电商行业中 获取销售订单的详细信息是一项重要且繁琐的任务 传统的方法是手动登录亚马逊平台 逐个查看订单并复制粘贴相关信息 这不仅耗费大量时间和人力资源 还容易出现错误和遗漏 八爪鱼rpa作为一款强大的机器人流程自动化工具可以帮助企业自动化
  • 智能机器人:未来与现实的交汇

    导言 人工智能智能机器人是当今科技领域的璀璨明珠 将技术 感知和智能相结合 呈现出前所未有的发展态势 人工智能助力的智能机器人代表了科技融合的巅峰 其强大的感知 学习和决策能力正深刻改变着我们的生活 本文将深入探讨人工智能智能机器人的定义
  • 机器人制作开源方案 | 智能水果分拣机器人

    作者 史振鹏 岳欣宇 仲祝伟 单位 邢台学院 指导老师 王承林 魏亚清 一 场景调研 智能水果分拣机器人是基于探索者设计的一款可搬运可分拣以及移动的一款轻便机器人 集成了语音控制 分拣 搬运 识别 抓取等功能 全部是使用探索者标准件 通过控
  • Pytorch深度强化学习案例:基于Q-Learning的机器人走迷宫

    目录 0 专栏介绍 1 Q Learning算法原理 2 强化学习基本框架 3 机器人走迷宫算法 3 1 迷宫环境 3 2 状态 动作和奖励 3 3 Q Learning算法实现 3 4 完成训练
  • ros2+xacro文件示例代码备份

    重要提示 在xacro文件虽然是xml文件 但是如果在xacro文件中随意插入自定义标签 虽然check urdf不会报错 但是最后rviz2解析的时候会出现错误 例如 如果在上述xml文件中加入以下代码将出现显示异常
  • Caught exception in launch(see debug for traceback)

    Caught exception in launch see debug for traceback Caught exception when trying to load file of format xml Caught except
  • ros2 学习07 rclpy包 详解

    rclpy 是 python 操作ros2 封装的一个工具包 rclpy 源码路径 https github com ros2 rclpy 文档说明地址 https docs ros2 org latest api rclpy index
  • 如何访问 Heroku 中的 docker 容器?

    我已按照此处构建图像的说明进行操作 https devcenter heroku com articles container registry and runtime getting started https devcenter her
  • 可以在catkin工作区之外创建ROS节点吗?

    我想在catkin工作区之外创建一个ROS发布者节点 可以创建吗 当然可以 像对待任何其他 cpp 库或 python 包一样对待 ROS 在Python中你必须保留PYTHONPATH环境变量指向ros包 opt ros kinetic
  • ros2 基础学习 15- URDF:机器人建模方法

    URDF 机器人建模方法 ROS是机器人操作系统 当然要给机器人使用啦 不过在使用之前 还得让ROS认识下我们使用的机器人 如何把一个机器人介绍给ROS呢 为此 ROS专门提供了一种机器人建模方法 URDF Unified Robot De
  • gazebo(fortress) set the path of sdf file

    This method only satisfied with gazebo fortress not harmenic
  • 如何从里程计/tf数据获取投影矩阵?

    我想将视觉里程计的结果与 KITTI 数据集提供的事实进行比较 对于地面中的每一帧 我都有一个投影矩阵 例如 1 000000e 00 9 043683e 12 2 326809e 11 1 110223e 16 9 043683e 12
  • 无法在 Ubuntu 20.04 上安装 ROS Melodic

    我正在尝试使用这些命令在 Ubuntu 20 04 上安装 ROS Melodic sudo sh c echo deb http packages ros org ros ubuntu lsb release sc main gt etc
  • 如何使用一个凉亭同时创建两个地图?

    如下图所示 现在我的gazebo正在运行2个slam gmapping包 首先是 turtlebot slam gmapping 发布到 map 主题 第二个是 slam gmapping 发布到与第一个相同的 map 主题 我想创建一个新
  • 安装 ROS 时 Cmake 未检测到 boost-python

    我一直在尝试在我的 Mac 上安装 ROS 并根据不同版本的 boost 使用不同的库解决了错误 然而 似乎有一个库甚至没有检测到 boost python 这是我得到的错误 CMake Error at usr local share c

随机推荐