ROS nav_msgs/Path.msg数据结构
0.引言
遇到一个记录一个。
- rviz中单位为m
1.nav_msgs/Path.msg
- ref
注意msg是poses也就是pose构成的数组,因此path的数据是一直递增不清除的。换句话讲就是要注意path的作用域,一般定义为全局变量或定义在main函数里或定义为static变量。
#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 = 0.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;
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;
}
2.geometry_msgs/TransformStamped.msg
geometry_msgs/Transform定义的就是frame_id与child_frame_id之间的变换。
3.tf2_msgs/TFMessage
4.nav_msgs/OccupancyGrid
ros::Publisher mapPub = nodeHandler.advertise<nav_msgs::OccupancyGrid>("laser_map", 1, true);
//发布地图.
void PublishMap(ros::Publisher &map_pub)
{
nav_msgs::OccupancyGrid rosMap;
rosMap.info.resolution = mapParams.resolution;
rosMap.info.origin.position.x = 0.0;
rosMap.info.origin.position.y = 0.0;
rosMap.info.origin.position.z = 0.0;
rosMap.info.origin.orientation.x = 0.0;
rosMap.info.origin.orientation.y = 0.0;
rosMap.info.origin.orientation.z = 0.0;
rosMap.info.origin.orientation.w = 1.0;
rosMap.info.origin.position.x = mapParams.origin_x;
rosMap.info.origin.position.y = mapParams.origin_y;
rosMap.info.width = mapParams.width;
rosMap.info.height = mapParams.height;
rosMap.data.resize(rosMap.info.width * rosMap.info.height);
//0~100
int cnt0, cnt1, cnt2;
cnt0 = cnt1 = cnt2 = 100;
for (int i = 0; i < mapParams.width * mapParams.height; i++)
{
if (pMap[i] == 50)
{
rosMap.data[i] = -1.0;
}
else
{
rosMap.data[i] = pMap[i];
}
}
rosMap.header.stamp = ros::Time::now();
rosMap.header.frame_id = "map";
map_pub.publish(rosMap);
}
5.nav_msgs/Odometry