博客
关于我
强烈建议你试试无所不能的chatGPT,快点击我
ROS在rviz中实时显示轨迹(nav_msgs/Path消息的使用)
阅读量:5175 次
发布时间:2019-06-13

本文共 2502 字,大约阅读时间需要 8 分钟。

消息结构说明

nav_msgs/Path.msg结构
#An array of poses that represents a Path for a robot to follow
Header header
geometry_msgs/PoseStamped[] poses
1
2
3
geometry_msgs/PoseStamped.msg结构
# A Pose with reference coordinate frame and timestamp
Header header
Pose pose
1
2
3
geometry_msgs/Pose.msg结构
# A representation of pose in free space, composed of position and orientation.
Point position
Quaternion orientation
1
2
3
geometry_msgs/Point.msg结构
# This contains the position of a point in free space
float64 x
float64 y
float64 z
1
2
3
4
geometry_msgs/Quaternion.msg结构
# This represents an orientation in free space in quaternion form.

float64 x

float64 y
float64 z
float64 w
1
2
3
4
5
6
实现代码:
#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 <tf/transform_broadcaster.h>
#include <tf/tf.h>

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::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 th = 0.0;
double vx = 0.1;
double vy = -0.1;
double vth = 0.1;

ros::Rate loop_rate(1);

while (ros::ok())
{

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

//compute odometry in a typical way given the velocities of the robot
double dt = (current_time - last_time).toSec();
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;
th += delta_th;

geometry_msgs::PoseStamped this_pose_stamped;
this_pose_stamped.pose.position.x = x;
this_pose_stamped.pose.position.y = 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);

ros::spinOnce(); // check for incoming messages

last_time = current_time;

loop_rate.sleep();
}

return 0;

}
--------------------- 

转载于:https://www.cnblogs.com/hyhy904/p/11001412.html

你可能感兴趣的文章
java 读写锁
查看>>
_itoa_s替换 itoa
查看>>
Nginx负载均衡
查看>>
【bzoj3456】城市规划(多项式求逆+dp)
查看>>
#ifdef 支持Mac #ifndef 支持Windows #if defined (Q_OS_WIN) 应该可以再两个系统通用
查看>>
linux源码中的核心数据结构
查看>>
EF执行SQL语句
查看>>
Ogre学习教程:Ogre1.8.1+VS2010环境配置2(转)
查看>>
webpack 样式表抽离成专门的单独文件并且设置版本号
查看>>
个人作业week7——前端开发感想总结
查看>>
VC Dimension -衡量模型与样本的复杂度
查看>>
android 中 ViewPager 的平常用法 ViewPager+ Views
查看>>
POJ 2449 Remmarguts' Date (SPFA + A星算法) - from lanshui_Yang
查看>>
ZOJ 1654 二分匹配基础题
查看>>
js笔记
查看>>
制作具有SSH、MySQL功能的Chroot
查看>>
TWaver html5 + NodeJS + express + websocket.io + redis 快速搭建项目(二)
查看>>
python 初学02 替换文件内容
查看>>
选择语句 if else
查看>>
STL中的set使用方法详细!!!!
查看>>