41 geometry_msgs::Twist
twist2Dto3D(
const nav_2d_msgs::Twist2D& cmd_vel_2d)
43 geometry_msgs::Twist cmd_vel;
44 cmd_vel.linear.x = cmd_vel_2d.x;
45 cmd_vel.linear.y = cmd_vel_2d.y;
46 cmd_vel.angular.z = cmd_vel_2d.theta;
51 nav_2d_msgs::Twist2D
twist3Dto2D(
const geometry_msgs::Twist& cmd_vel)
53 nav_2d_msgs::Twist2D cmd_vel_2d;
54 cmd_vel_2d.x = cmd_vel.linear.x;
55 cmd_vel_2d.y = cmd_vel.linear.y;
56 cmd_vel_2d.theta = cmd_vel.angular.z;
62 nav_2d_msgs::Pose2DStamped pose2d;
63 pose2d.header.stamp = pose.
stamp_;
65 pose2d.pose.x = pose.getOrigin().getX();
66 pose2d.pose.y = pose.getOrigin().getY();
67 pose2d.pose.theta =
tf::getYaw(pose.getRotation());
73 nav_2d_msgs::Pose2DStamped pose2d;
74 pose2d.header = pose.header;
75 pose2d.pose.x = pose.pose.position.x;
76 pose2d.pose.y = pose.pose.position.y;
77 pose2d.pose.theta =
tf::getYaw(pose.pose.orientation);
81 geometry_msgs::Pose
pose2DToPose(
const geometry_msgs::Pose2D& pose2d)
83 geometry_msgs::Pose pose;
84 pose.position.x = pose2d.x;
85 pose.position.y = pose2d.y;
92 geometry_msgs::PoseStamped pose;
93 pose.header = pose2d.header;
99 const std::string& frame,
const ros::Time& stamp)
101 geometry_msgs::PoseStamped pose;
102 pose.header.frame_id = frame;
103 pose.header.stamp = stamp;
104 pose.pose.position.x = pose2d.x;
105 pose.pose.position.y = pose2d.y;
112 nav_2d_msgs::Path2D path2d;
113 path2d.header = path.header;
114 nav_2d_msgs::Pose2DStamped stamped_2d;
115 path2d.poses.resize(path.poses.size());
116 for (
unsigned int i = 0; i < path.poses.size(); i++)
119 path2d.poses[i] = stamped_2d.pose;
124 nav_msgs::Path
posesToPath(
const std::vector<geometry_msgs::PoseStamped>& poses)
130 path.poses.resize(poses.size());
131 path.header.frame_id = poses[0].header.frame_id;
132 path.header.stamp = poses[0].header.stamp;
133 for (
unsigned int i = 0; i < poses.size(); i++)
135 path.poses[i] = poses[i];
140 nav_2d_msgs::Path2D
posesToPath2D(
const std::vector<geometry_msgs::PoseStamped>& poses)
142 nav_2d_msgs::Path2D path;
146 nav_2d_msgs::Pose2DStamped pose;
147 path.poses.resize(poses.size());
148 path.header.frame_id = poses[0].header.frame_id;
149 path.header.stamp = poses[0].header.stamp;
150 for (
unsigned int i = 0; i < poses.size(); i++)
153 path.poses[i] = pose.pose;
159 nav_msgs::Path
poses2DToPath(
const std::vector<geometry_msgs::Pose2D>& poses,
160 const std::string& frame,
const ros::Time& stamp)
163 path.poses.resize(poses.size());
164 path.header.frame_id = frame;
165 path.header.stamp = stamp;
166 for (
unsigned int i = 0; i < poses.size(); i++)
176 path.header = path2d.header;
177 path.poses.resize(path2d.poses.size());
178 for (
unsigned int i = 0; i < path.poses.size(); i++)
180 path.poses[i].header = path2d.header;
188 nav_2d_msgs::NavGridInfo msg;
189 msg.width = info.
width;
201 info.
width = msg.width;
214 info.
width = metadata.width;
215 info.
height = metadata.height;
216 info.
origin_x = metadata.origin.position.x;
217 info.
origin_y = metadata.origin.position.y;
218 if (std::abs(
tf::getYaw(metadata.origin.orientation)) > 1e-5)
221 "Conversion from MapMetaData to NavGridInfo encountered a non-zero rotation. Ignoring.");
228 nav_msgs::MapMetaData metadata;
230 metadata.width = info.
width;
231 metadata.height = info.
height;
232 metadata.origin.position.x = info.
origin_x;
233 metadata.origin.position.y = info.
origin_y;
234 metadata.origin.orientation.w = 1.0;
240 nav_2d_msgs::UIntBounds msg;
unsigned int getMaxX() const
geometry_msgs::Pose pose2DToPose(const geometry_msgs::Pose2D &pose2d)
#define ROS_WARN_NAMED(name,...)
unsigned int getMinX() const
unsigned int getMinY() const
static double getYaw(const Quaternion &bt_q)
nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo &info)
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
nav_grid::NavGridInfo fromMsg(const nav_2d_msgs::NavGridInfo &msg)
geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D &cmd_vel_2d)
nav_msgs::Path posesToPath(const std::vector< geometry_msgs::PoseStamped > &poses)
nav_2d_msgs::Path2D posesToPath2D(const std::vector< geometry_msgs::PoseStamped > &poses)
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
nav_msgs::Path poses2DToPath(const std::vector< geometry_msgs::Pose2D > &poses, const std::string &frame, const ros::Time &stamp)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
nav_2d_msgs::Pose2DStamped stampedPoseToPose2D(const tf::Stamped< tf::Pose > &pose)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
unsigned int getMaxY() const
nav_grid::NavGridInfo infoToInfo(const nav_msgs::MapMetaData &metadata)
nav_2d_msgs::Twist2D twist3Dto2D(const geometry_msgs::Twist &cmd_vel)