37 #include <geometry_msgs/PoseStamped.h> 48 std::string from_topic,
49 std::string to_topic);
52 void transform(
const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
66 double x,
double y,
double z,
68 std::string from_topic, std::string to_topic):
84 const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
86 Eigen::Affine3d input_transform;
88 Eigen::AngleAxisd roll_angle(
roll_, Eigen::Vector3d::UnitZ());
89 Eigen::AngleAxisd yaw_angle(
yaw_, Eigen::Vector3d::UnitY());
90 Eigen::AngleAxisd pitch_angle(
pitch_, Eigen::Vector3d::UnitX());
92 Eigen::Affine3d transformation
93 = Eigen::Translation3d(
x_,
y_,
z_) * roll_angle * yaw_angle * pitch_angle;
94 Eigen::Affine3d output_transform = input_transform * transformation;
95 geometry_msgs::PoseStamped output_pose_msg;
97 output_pose_msg.header = pose_msg->header;
105 std::cerr <<
"Usage:: " << argv[0]
106 <<
" x y z yaw pitch roll from_topic to_topic" 112 ros::init(argc, argv,
"static_transform_pose_stamped",
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)