ROSNOTE : 定义雷达数据,发送速度消息

 

 

 

 

/*********************************************************************
* Software License Agreement (BSD License)
* 
*  Copyright (c) 2017-2020, Waterplus http://www.6-robot.com
*  All rights reserved.
* 
*  Redistribution and use in source and binary forms, with or without
*  modification, are permitted provided that the following conditions
*  are met:
* 
*   * Redistributions of source code must retain the above copyright
*     notice, this list of conditions and the following disclaimer.
*   * Redistributions in binary form must reproduce the above
*     copyright notice, this list of conditions and the following
*     disclaimer in the documentation and/or other materials provided
*     with the distribution.
*   * Neither the name of the WaterPlus nor the names of its
*     contributors may be used to endorse or promote products derived
*     from this software without specific prior written permission.
* 
*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
*  FOOTPRINTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
*  POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/*!******************************************************************
 @author     ZhangWanjie
 ********************************************************************/

#include <ros/ros.h>
#include <std_msgs/String.h>
//String.h是字符格式的定义文件,用来做文字输出
#include <sensor_msgs/LaserScan.h>
//LaserScan.h是激光雷达的数据格式定义文件,用来装载雷达数
#include <geometry_msgs/Twist.h>
//Twist.h是机器运动速度消息包的格式定义文件

ros::Publisher vel_pub;
//定义消息发布对象,会用这个发布对象向机器人核心节点发送速度控制消息包
static int nCount = 0;
//调整机器人转向动作的时长

//定义一个回调函数void lidarCallback(),用来处理激光雷达数据,雷达的测距数值会以参数的形式传递到这个回调函数里。
void lidarCallback(const sensor_msgs::LaserScan::ConstPtr& scan)
{
    int nNum = scan->ranges.size();
    
    int nMid = nNum/2;
    float fMidDist = scan->ranges[nMid];
    ROS_INFO("Point[%d] = %f", nMid, fMidDist); 

    if(nCount > 0)
    {
        nCount--;
        return;
    }

    geometry_msgs::Twist vel_cmd;
    //根据fMidDist的数值大小来对vel_cmd进行不同的赋值
    if(fMidDist > 1.5f)
    {
        vel_cmd.linear.x = 0.05;
    }
    else
    {
        vel_cmd.angular.z = 0.3;
        nCount = 50;
    }
    vel_pub.publish(vel_cmd);
}

int main(int argc, char** argv)
{
    ros::init(argc,argv,"wpb_home_lidar_behavior");
    
    ROS_INFO("wpb_home_lidar_behavior start!");

    ros::NodeHandle nh;
    
    ros::Subscriber lidar_sub = nh.subscribe("/scan", 10, &lidarCallback);
    //定义一个ros::NodeHandle节点句柄nh,并使用这个句柄向ROS核心节点订阅“/scan”主题的数据,回调函数设置为之前定义的lidarCallback()。
    vel_pub = nh.advertise<geometry_msgs::Twist>("/cmd_vel",10);
    //让其在主题“/cmd_vel”发布速度控制消息,启智ROS的核心节点会从这个主题获取vel_pub发布的消息,并控制机器人底盘执行消息包里的速度值。
    ros::spin();
    
}

 

评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值