ROS在rviz中实时显示轨迹和点

8 篇文章 3 订阅

记录一个简单的例子方便复制:
通过使用

nav_msgs::Path
geometry_msgs::PoseStamped
geometry_msgs::PointStamped

来实现rviz中可视化轨迹和轨迹点。
首先创建工程:

mkdir -p showpath/src
cd src
catkin_create_pkg showpath roscpp rospy sensor_msgs std_msgs nav_msgs tf
cd ..
catkin_make 

以及修改cmakelist:

add_executable(showpath src/showpath.cpp)
target_link_libraries(showpath ${catkin_LIBRARIES})

编译和运行:

catkin build
source ./devel/setup.bash//别忘了source

roscore
rosrun showpath showpath
rostopic echo /trajectory
rostopic echo /point
rosrun rviz rviz

代码部分:

#include <ros/ros.h>
#include <ros/console.h>
#include <nav_msgs/Path.h>
#include <std_msgs/String.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/PointStamped.h>
#include <tf/transform_broadcaster.h>
#include <tf/tf.h>
#include <cstdlib>

main(int argc, char **argv)
{
    ros::init(argc, argv, "showpath");

    ros::NodeHandle ph;
    ros::Publisher path_pub = ph.advertise<nav_msgs::Path>("trajectory", 1, true);
    ros::Publisher point_pub = ph.advertise<geometry_msgs::PointStamped>("point", 1, true);

    ros::Time current_time, last_time;
    current_time = ros::Time::now();
    last_time = ros::Time::now();

    nav_msgs::Path path;

    //nav_msgs::Path path;
    path.header.stamp = current_time;
    path.header.frame_id = "odom";

    double x = 0.0;
    double y = 0.0;
    double z = 0.0;
    double th = 0.0;
    double vx = 0.1 + 0.2 * rand() / double(RAND_MAX);
    double vy = -0.1 + 0.2 * rand() / double(RAND_MAX);
    double vth = 0.1;

    ros::Rate loop_rate(10);
    while (ros::ok())
    {

        current_time = ros::Time::now();
        //compute odometry in a typical way given the velocities of the robot
        double dt = 1;
        double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
        double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
        double delta_th = vth * dt;

        x += delta_x;
        y += delta_y;
        z += 0.005;
        th += delta_th;

        geometry_msgs::PoseStamped this_pose_stamped;
        geometry_msgs::PointStamped this_point_stamped;

        this_pose_stamped.pose.position.x = x;
        this_pose_stamped.pose.position.y = y;
        this_pose_stamped.pose.position.z = z;

        this_point_stamped.header.stamp = current_time;
        this_point_stamped.header.frame_id = "odom";
        this_point_stamped.point.x = x;
        this_point_stamped.point.y = y;
        this_point_stamped.point.z = z;
        ROS_INFO("current_x: %f", x);
        ROS_INFO("current_y: %f", y);
        geometry_msgs::Quaternion goal_quat = tf::createQuaternionMsgFromYaw(th);
        this_pose_stamped.pose.orientation.x = goal_quat.x;
        this_pose_stamped.pose.orientation.y = goal_quat.y;
        this_pose_stamped.pose.orientation.z = goal_quat.z;
        this_pose_stamped.pose.orientation.w = goal_quat.w;

        this_pose_stamped.header.stamp = current_time;
        this_pose_stamped.header.frame_id = "odom";
        path.poses.push_back(this_pose_stamped);

        path_pub.publish(path);
        point_pub.publish(this_point_stamped);
        ros::spinOnce(); // check for incoming messages

        last_time = current_time;
        loop_rate.sleep();
    }

    return 0;
}

rviz中globel option的Fixed Fram输入odom
左边点击add
选中path
在path的topic选项中选
/trajectory和/point

add对应topicsadd对应topics

修改对齐frame_id的odom修改对齐frame_id的odom

选择trajectory和 point

效果如下:
在这里插入图片描述

  • 18
    点赞
  • 160
    收藏
    觉得还不错? 一键收藏
  • 4
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 4
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值