diff --git a/include/odometry_transformer/odometry_transformer.h b/include/odometry_transformer/odometry_transformer.h index 53adf6e..a3be755 100644 --- a/include/odometry_transformer/odometry_transformer.h +++ b/include/odometry_transformer/odometry_transformer.h @@ -6,7 +6,10 @@ #include #include + #include +#include + #include #include @@ -23,6 +26,7 @@ class OdometryTransformer { private: void receiveOdometry(const nav_msgs::OdometryConstPtr &source_odometry); + void receivePose(const geometry_msgs::PoseWithCovarianceStampedPtr &source_odometry); void broadcastCalibration(); void initializeDynamicReconfigure(); @@ -33,6 +37,7 @@ class OdometryTransformer { std::string target_frame_ = ""; int queue_size_ = 1; bool tcp_no_delay_ = false; + bool pose_transform_ = false; // Optionally publish TF and offer dynamic reconfigure if calibration is set // from ROS parameter server. @@ -49,6 +54,9 @@ class OdometryTransformer { ros::Subscriber odometry_sub_; ros::Publisher odometry_pub_; + + ros::Subscriber pose_sub_; + ros::Publisher pose_pub_; }; } // namespace odometry_transformer diff --git a/launch/odometry_transformer.launch b/launch/odometry_transformer.launch index dc8dabf..a0881bb 100644 --- a/launch/odometry_transformer.launch +++ b/launch/odometry_transformer.launch @@ -3,6 +3,14 @@ + + + + + + + + @@ -26,6 +34,9 @@ + + + @@ -36,5 +47,7 @@ + + diff --git a/src/odometry_transformer.cc b/src/odometry_transformer.cc index 1b65f6a..7929cdc 100644 --- a/src/odometry_transformer.cc +++ b/src/odometry_transformer.cc @@ -85,6 +85,14 @@ void OdometryTransformer::getRosParameters() { } else { ROS_INFO("TCP no delay de-activated."); } + + // Pose transform as well + nh_private_.getParam("pose_transform", pose_transform_); + if (pose_transform_) { + ROS_INFO("Pose transform activated."); + } else { + ROS_INFO("Pose transform de-activated."); + } } void OdometryTransformer::subscribeToRosTopics() { @@ -96,12 +104,27 @@ void OdometryTransformer::subscribeToRosTopics() { ? ros::TransportHints().tcpNoDelay() : ros::TransportHints()); ROS_INFO("Subscribed to %s", odometry_sub_.getTopic().c_str()); + + if(pose_transform_){ + pose_sub_ = nh_.subscribe("source_pose", + queue_size_, + &OdometryTransformer::receivePose, + this, + tcp_no_delay_ + ? ros::TransportHints().tcpNoDelay() + : ros::TransportHints()); + ROS_INFO("Subscribed to %s", pose_sub_.getTopic().c_str()); + } } void OdometryTransformer::advertiseRosTopics() { odometry_pub_ = nh_.advertise("target_odometry", queue_size_); ROS_INFO("Advertising %s", odometry_pub_.getTopic().c_str()); + + pose_pub_ = + nh_.advertise("target_pose", queue_size_); + ROS_INFO("Advertising %s", pose_pub_.getTopic().c_str()); } void OdometryTransformer::broadcastCalibration() { @@ -213,4 +236,26 @@ void OdometryTransformer::receiveOdometry( odometry_pub_.publish(target_odometry); } +void OdometryTransformer::receivePose( + const geometry_msgs::PoseWithCovarianceStampedPtr &source_pose) { + ROS_INFO_ONCE("Received first pose message."); + + // Get source pose in inertial/world coordinate frame. + Eigen::Affine3d T_IS; + Eigen::fromMsg(source_pose->pose.pose, T_IS); + + // Compute pose of target frame. + const Eigen::Affine3d T_IT = T_IS * T_ST_; + + // Convert to target odometry. + geometry_msgs::PoseWithCovarianceStamped target_pose; + target_pose.header = source_pose->header; + target_pose.pose.pose = Eigen::toMsg(T_IT); + + // TODO(TimonMathis): Transform covariance. + + // Publish transformed odometry. + pose_pub_.publish(target_pose); +} + } // namespace odometry_transformer diff --git a/test/launch/test_pose_transform.launch b/test/launch/test_pose_transform.launch new file mode 100644 index 0000000..ac606b9 --- /dev/null +++ b/test/launch/test_pose_transform.launch @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + $(arg q_TS) + $(arg T_r_TS) + + + + + + + + +