4 #include <eigen3/Eigen/Dense>
6 #include <geometry_msgs/Pose.h>
13 inline geometry_msgs::Pose&
copy(
const Eigen::Vector3d &src, geometry_msgs::Pose &des){
14 double cy = cos ( src[2] * 0.5 );
15 double sy = sin ( src[2] * 0.5 );
17 des.position.x = src[0], des.position.y = src[1], des.position.z = 0;
18 des.orientation.w = cy;
19 des.orientation.x = 0.;
20 des.orientation.y = 0.;
21 des.orientation.z = sy;
24 inline geometry_msgs::Pose
copy(
const Eigen::Vector3d &src){
25 geometry_msgs::Pose des;
29 inline Eigen::Vector3d&
copy(
const geometry_msgs::Pose &src, Eigen::Vector3d &des){
30 double siny = +2.0 * ( src.orientation.w * src.orientation.z + src.orientation.x * src.orientation.y );
31 double cosy = +1.0 - 2.0 * ( src.orientation.y * src.orientation.y + src.orientation.z * src.orientation.z );
32 double yaw = atan2 ( siny, cosy );
33 des = Eigen::Vector3d (src.position.x, src.position.y, yaw );
36 inline Eigen::Vector3d
copy(
const geometry_msgs::Pose &src){
97 bool updatedPc =
false;
101 if (pc.robotId == n_pc.
robotId)
103 pc.stepCondition = std::max(pc.stepCondition, n_pc.
stepCondition);
122 bool updatedPc =
false;
126 if (pc.robotId == n_pc.robotId)
128 pc.stepCondition = std::max(pc.stepCondition, n_pc.stepCondition);