diff --git a/stdr_robot/CMakeLists.txt b/stdr_robot/CMakeLists.txt index 62113bf3..c0a59fda 100644 --- a/stdr_robot/CMakeLists.txt +++ b/stdr_robot/CMakeLists.txt @@ -6,6 +6,7 @@ find_package(catkin REQUIRED COMPONENTS nodelet actionlib tf + tf2_ros stdr_msgs stdr_parser geometry_msgs @@ -30,6 +31,7 @@ catkin_package( nodelet actionlib tf + tf2_ros stdr_msgs stdr_parser geometry_msgs diff --git a/stdr_robot/include/stdr_robot/stdr_robot.h b/stdr_robot/include/stdr_robot/stdr_robot.h index e31e9858..546a15f4 100644 --- a/stdr_robot/include/stdr_robot/stdr_robot.h +++ b/stdr_robot/include/stdr_robot/stdr_robot.h @@ -25,6 +25,7 @@ #include #include #include +#include #include #include #include @@ -150,6 +151,9 @@ namespace stdr_robot { //!< ROS tf transform broadcaster tf::TransformBroadcaster _tfBroadcaster; + //!< ROS tf2 static transform broadcaster + tf2_ros::StaticTransformBroadcaster _tfStaticBroadcaster; + //!< Odometry Publisher ros::Publisher _odomPublisher; diff --git a/stdr_robot/package.xml b/stdr_robot/package.xml index 1cfa5cb3..6919001e 100644 --- a/stdr_robot/package.xml +++ b/stdr_robot/package.xml @@ -18,6 +18,7 @@ roscpp tf + tf2_ros sensor_msgs stdr_msgs stdr_parser diff --git a/stdr_robot/src/stdr_robot.cpp b/stdr_robot/src/stdr_robot.cpp index a3128eed..a3ed0968 100644 --- a/stdr_robot/src/stdr_robot.cpp +++ b/stdr_robot/src/stdr_robot.cpp @@ -60,9 +60,9 @@ namespace stdr_robot _moveRobotService = n.advertiseService( getName() + "/replace", &Robot::moveRobotCallback, this); - //we should not start the timer, until we hame a motion controller + //we should not start the timer, until we have a motion controller _tfTimer = n.createTimer( - ros::Duration(0.1), &Robot::publishTransforms, this, false, false); + ros::Duration(0.01), &Robot::publishTransforms, this, false, false); } /** @@ -172,6 +172,27 @@ namespace stdr_robot new IdealMotionController(_currentPose, _tfBroadcaster, n, getName(), p)); } + //!< Sensors static tfs + for (int i = 0; i < _sensors.size(); i++) { + geometry_msgs::Pose2D sensorPose = _sensors[i]->getSensorPose(); + + geometry_msgs::TransformStamped transformStamped; + + transformStamped.header.stamp = ros::Time::now(); + transformStamped.header.frame_id = getName(); + transformStamped.child_frame_id = _sensors[i]->getFrameId(); + transformStamped.transform.translation.x = sensorPose.x; + transformStamped.transform.translation.y = sensorPose.y; + transformStamped.transform.translation.z = 0.0; + tf2::Quaternion quat; + quat.setRPY(0.0, 0.0, sensorPose.theta); + transformStamped.transform.rotation.x = quat.x(); + transformStamped.transform.rotation.y = quat.y(); + transformStamped.transform.rotation.z = quat.z(); + transformStamped.transform.rotation.w = quat.w(); + _tfStaticBroadcaster.sendTransform(transformStamped); + } + _tfTimer.start(); } @@ -407,7 +428,7 @@ namespace stdr_robot } /** - @brief Publishes the tf transforms every with 10Hz + @brief Publishes the tf transforms every with 100Hz @return void **/ void Robot::publishTransforms(const ros::TimerEvent&) @@ -422,6 +443,7 @@ namespace stdr_robot _motionControllerPtr->setPose(_previousPose); } //!< Robot tf + ros::Time timeNow = ros::Time::now(); tf::Vector3 translation(_previousPose.x, _previousPose.y, 0); tf::Quaternion rotation; rotation.setRPY(0, 0, _previousPose.theta); @@ -429,11 +451,11 @@ namespace stdr_robot tf::Transform mapToRobot(rotation, translation); _tfBroadcaster.sendTransform(tf::StampedTransform( - mapToRobot, ros::Time::now(), "map_static", getName())); + mapToRobot, timeNow, "map_static", getName())); //!< Odometry nav_msgs::Odometry odom; - odom.header.stamp = ros::Time::now(); + odom.header.stamp = timeNow; odom.header.frame_id = "map_static"; odom.child_frame_id = getName(); odom.pose.pose.position.x = _previousPose.x; @@ -442,25 +464,7 @@ namespace stdr_robot _previousPose.theta); odom.twist.twist = _motionControllerPtr->getVelocity(); - _odomPublisher.publish(odom); - - //!< Sensors tf - for (int i = 0; i < _sensors.size(); i++) { - geometry_msgs::Pose2D sensorPose = _sensors[i]->getSensorPose(); - - tf::Vector3 trans(sensorPose.x, sensorPose.y, 0); - tf::Quaternion rot; - rot.setRPY(0, 0, sensorPose.theta); - - tf::Transform robotToSensor(rot, trans); - - _tfBroadcaster.sendTransform( - tf::StampedTransform( - robotToSensor, - ros::Time::now(), - getName(), - _sensors[i]->getFrameId())); - } + _odomPublisher.publish(odom); } /**