|
From: <tf...@us...> - 2009-07-02 21:37:33
|
Revision: 18230
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18230&view=rev
Author: tfoote
Date: 2009-07-02 21:27:56 +0000 (Thu, 02 Jul 2009)
Log Message:
-----------
taking care of #1704
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/src/add_calibration_data.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_trajectory_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/plug_controller.cpp
pkg/trunk/demos/plug_in/src/servo.cpp
pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_tongs.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_grasp_handle.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_push_door.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_release_handle.cpp
pkg/trunk/highlevel/doors/doors_core/src/action_touch_door.cpp
pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp
pkg/trunk/highlevel/doors/doors_core/test/test_planner.cpp
pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in.cpp
pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in2.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp
pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp
pkg/trunk/highlevel/writing/writing_test/src/test_move_to_helper.cpp
pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp
pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/src/pr2_arm_node.cpp
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp
pkg/trunk/nav/people_aware_nav/src/is_person_on_path.cpp
pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp
pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp
pkg/trunk/nav/visual_nav/src/ros_visual_nav.cpp
pkg/trunk/nav/wavefront/src/cli.cpp
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/sandbox/descriptors_3d/.build_version
pkg/trunk/sandbox/descriptors_3d/.rosgcov_files
pkg/trunk/sandbox/labeled_object_detector/src/planar_object_detector.cpp
pkg/trunk/sandbox/poseviz/src/poseviz.cpp
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp
pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
pkg/trunk/stacks/geometry/tf/src/change_notifier.cpp
pkg/trunk/stacks/geometry/tf/src/tf.cpp
pkg/trunk/stacks/geometry/tf/src/transform_broadcaster.cpp
pkg/trunk/stacks/geometry/tf/src/transform_listener.cpp
pkg/trunk/stacks/geometry/tf/test/tf_unittest.cpp
pkg/trunk/stacks/geometry/tf_tutorials/src/shuttle_observer.cpp
pkg/trunk/stacks/geometry/tf_tutorials/src/tutorial_listener.cpp
pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
pkg/trunk/stacks/mechanism/robot_state_publisher/src/robot_state_publisher.cpp
pkg/trunk/stacks/nav/amcl/src/amcl_node.cpp
pkg/trunk/stacks/nav/base_local_planner/src/trajectory_planner_ros.cpp
pkg/trunk/stacks/nav/fake_localization/fake_localization.cpp
pkg/trunk/stacks/nav/move_base/src/move_base.cpp
pkg/trunk/stacks/nav/nav_view/src/nav_view/nav_view_panel.cpp
pkg/trunk/stacks/nav/nav_view/src/nav_view/tools.cpp
pkg/trunk/stacks/nav/navfn/src/navfn_ros.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/door_checkerboard_detector.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/test_door_detection.cpp
pkg/trunk/stacks/semantic_mapping/door_handle_detector/test/test_door_detection_joystick.cpp
pkg/trunk/stacks/trex/trex_pr2/src/pr2_components.cpp
pkg/trunk/stacks/trex/trex_pr2/src/topological_map.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/calibrate_plug.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_spotting2.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_tracker.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/outlet_util.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/plug_tracker.cpp
pkg/trunk/stacks/visual_feature_detectors/outlet_detection/src/tracker_base.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/displays/particle_cloud_2d_display.cpp
pkg/trunk/stacks/visualization/rviz/src/rviz/tools/pose_tool.cpp
pkg/trunk/util/pr2_ik/src/pr2_ik_controller.cpp
pkg/trunk/util/pr2_ik/src/pr2_ik_node.cpp
pkg/trunk/vision/people/src/face_detection.cpp
pkg/trunk/vision/people/src/filter/people_tracking_node.cpp
pkg/trunk/vision/people/src/leg_detector.cpp
pkg/trunk/vision/people/src/stereo_color_tracker.cpp
pkg/trunk/vision/people/src/stereo_face_color_tracker.cpp
pkg/trunk/vision/stereo_checkerboard_detector/src/stereo_checkerboard_node.cpp
Modified: pkg/trunk/calibration/kinematic_calibration/src/add_calibration_data.cpp
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/add_calibration_data.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/calibration/kinematic_calibration/src/add_calibration_data.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -123,15 +123,15 @@
list< pair<string, double> > calib_params ;
tf::Transform stereo_final_T ;
- tf::TransformMsgToTF(robot_cal_.stereo_final, stereo_final_T) ;
+ tf::transformMsgToTF(robot_cal_.stereo_final, stereo_final_T) ;
getCamCorrection(calib_params, robot_, stereo_final_T, "stereo") ;
tf::Transform high_res_final_T ;
- tf::TransformMsgToTF(robot_cal_.high_res_final, high_res_final_T) ;
+ tf::transformMsgToTF(robot_cal_.high_res_final, high_res_final_T) ;
getCamCorrection(calib_params, robot_, high_res_final_T, "high_res") ;
tf::Transform head_initial_T ;
- tf::TransformMsgToTF(robot_cal_.head_initial, head_initial_T) ;
+ tf::transformMsgToTF(robot_cal_.head_initial, head_initial_T) ;
getHeadInitialCorrection(calib_params, robot_, head_initial_T) ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -159,25 +159,25 @@
// Laser Chain
msg.transforms[0].parent_id = "torso_lift_link" ;
msg.transforms[0].header.frame_id = "laser_tilt_mount_link_cal" ;
- tf::TransformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
+ tf::transformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
msg.transforms[1].parent_id = "laser_tilt_mount_link_cal" ;
msg.transforms[1].header.frame_id = "laser_tilt_link_cal" ;
- tf::TransformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
+ tf::transformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
// Head Chain
msg.transforms[2].parent_id = "torso_lift_link" ;
msg.transforms[2].header.frame_id = "head_pan_link_cal" ;
- tf::TransformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
+ tf::transformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
msg.transforms[3].parent_id = "head_pan_link_cal" ;
msg.transforms[3].header.frame_id = "head_tilt_link_cal" ;
- //tf::TransformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
- tf::TransformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
+ //tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
+ tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
msg.transforms[4].parent_id = "head_tilt_link_cal" ;
msg.transforms[4].header.frame_id = "stereo_optical_frame_cal" ;
- tf::TransformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
+ tf::transformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
tf_pub_.publish(msg) ;
//printf("done!\n") ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_pre.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -163,25 +163,25 @@
// Laser Chain
msg.transforms[0].parent_id = "torso_lift_link" ;
msg.transforms[0].header.frame_id = "laser_tilt_mount_link_cal" ;
- tf::TransformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
+ tf::transformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
msg.transforms[1].parent_id = "laser_tilt_mount_link_cal" ;
msg.transforms[1].header.frame_id = "laser_tilt_link_cal" ;
- tf::TransformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
+ tf::transformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
// Head Chain
msg.transforms[2].parent_id = "torso_lift_link" ;
msg.transforms[2].header.frame_id = "head_pan_link_cal" ;
- tf::TransformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
+ tf::transformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
msg.transforms[3].parent_id = "head_pan_link_cal" ;
msg.transforms[3].header.frame_id = "head_tilt_link_cal" ;
- //tf::TransformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
- tf::TransformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
+ //tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
+ tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
msg.transforms[4].parent_id = "head_tilt_link_cal" ;
msg.transforms[4].header.frame_id = "stereo_optical_frame_cal" ;
- tf::TransformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
+ tf::transformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
tf_pub_.publish(msg) ;
//printf("done!\n") ;
Modified: pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp
===================================================================
--- pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/calibration/sandbox/laser_head_updater/src/publish_laser_head_tf_prg.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -162,25 +162,25 @@
// Laser Chain
msg.transforms[0].parent_id = "torso_lift_link" ;
msg.transforms[0].header.frame_id = "laser_tilt_mount_link_cal" ;
- tf::TransformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
+ tf::transformTFToMsg(laser_initial_T_*laser_joint_T, msg.transforms[0].transform) ;
msg.transforms[1].parent_id = "laser_tilt_mount_link_cal" ;
msg.transforms[1].header.frame_id = "laser_tilt_link_cal" ;
- tf::TransformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
+ tf::transformTFToMsg(laser_final_T_, msg.transforms[1].transform) ;
// Head Chain
msg.transforms[2].parent_id = "torso_lift_link" ;
msg.transforms[2].header.frame_id = "head_pan_link_cal" ;
- tf::TransformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
+ tf::transformTFToMsg(head_initial_T_*pan_joint_T, msg.transforms[2].transform) ;
msg.transforms[3].parent_id = "head_pan_link_cal" ;
msg.transforms[3].header.frame_id = "head_tilt_link_cal" ;
- //tf::TransformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
- tf::TransformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
+ //tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
+ tf::transformTFToMsg(after_pan_T_*tilt_joint_T, msg.transforms[3].transform) ;
msg.transforms[4].parent_id = "head_tilt_link_cal" ;
msg.transforms[4].header.frame_id = "stereo_optical_frame_cal" ;
- tf::TransformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
+ tf::transformTFToMsg(after_tilt_T_, msg.transforms[4].transform) ;
tf_pub_.publish(msg) ;
//printf("done!\n") ;
Modified: pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp
===================================================================
--- pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/calibration/wheel_odometry_calibration/src/odom_calib.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -91,7 +91,7 @@
{
_imu_mutex.lock();
double tmp, yaw; Transform tf;
- PoseMsgToTF(_imu.pos, tf);
+ poseMsgToTF(_imu.pos, tf);
tf.getBasis().getEulerZYX(yaw, tmp, tmp);
if (!_imu_active){
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_position_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -164,7 +164,7 @@
tf_.transformPose(odom_frame_name_, cmd, pose_odom) ;
tf::Quaternion orientation_odom ; // Orientation in the odometric frame
- tf::QuaternionMsgToTF(pose_odom.pose.orientation, orientation_odom) ;
+ tf::quaternionMsgToTF(pose_odom.pose.orientation, orientation_odom) ;
// For convenience, use 1-Letter names for quaternion terms
const double& w = orientation_odom.w() ;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -382,7 +382,7 @@
string mount_link_name = "laser_tilt_mount_link" ;
target_link_ = robot_->getLinkState(track_link_cmd.link_name) ;
mount_link_ = robot_->getLinkState(mount_link_name) ;
- tf::PointMsgToTF(track_link_cmd.point, track_point_) ;
+ tf::pointMsgToTF(track_link_cmd.point, track_point_) ;
if (target_link_ == NULL)
{
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -51,7 +51,7 @@
{
tf::Transform tf;
tf::TransformKDLToTF(k, tf);
- tf::PoseTFToMsg(tf, m);
+ tf::poseTFToMsg(tf, m);
}
void TwistKDLToMsg(const KDL::Twist &k, robot_msgs::Twist &m)
@@ -545,7 +545,7 @@
pub_tf_->msg_.transforms[0].parent_id = c_.chain_.getLinkName();
tf::Transform t;
tf::TransformKDLToTF(c_.tool_frame_offset_, t);
- tf::TransformTFToMsg(t, pub_tf_->msg_.transforms[0].transform);
+ tf::transformTFToMsg(t, pub_tf_->msg_.transforms[0].transform);
pub_tf_->unlockAndPublish();
}
}
@@ -608,7 +608,7 @@
robot_msgs::PoseStamped tool_in_tip_msg;
tf::Transform tool_in_tip;
TF.transformPose(c_.chain_.getLinkName(-1), req.p, tool_in_tip_msg);
- tf::PoseMsgToTF(tool_in_tip_msg.pose, tool_in_tip);
+ tf::poseMsgToTF(tool_in_tip_msg.pose, tool_in_tip);
tool_in_tip.setOrigin(tf::Vector3(0,0,0));
tf::TransformTFToKDL(tool_in_tip, c_.tool_frame_offset_);
double rpy[3]; c_.tool_frame_offset_.M.GetRPY(rpy[0], rpy[1], rpy[2]);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -188,7 +188,7 @@
if (state_pose_publisher_->trylock()){
Pose tmp;
frameToPose(pose_meas_, tmp);
- PoseStampedTFToMsg(Stamped<Pose>(tmp, ros::Time::now(), root_name_), state_pose_publisher_->msg_);
+ poseStampedTFToMsg(Stamped<Pose>(tmp, ros::Time::now(), root_name_), state_pose_publisher_->msg_);
state_pose_publisher_->unlockAndPublish();
}
}
@@ -213,7 +213,7 @@
{
// convert message to transform
Stamped<Pose> pose_stamped;
- PoseStampedMsgToTF(*pose_msg, pose_stamped);
+ poseStampedMsgToTF(*pose_msg, pose_stamped);
// convert to reference frame of root link of the controller chain
tf_.transformPose(root_name_, pose_stamped, pose_stamped);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_trajectory_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_trajectory_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -147,7 +147,7 @@
// convert message to transform
Stamped<Pose> pose_stamped;
- PoseStampedMsgToTF(pose, pose_stamped);
+ poseStampedMsgToTF(pose, pose_stamped);
// convert to reference frame of root link of the controller chain
Duration timeout = Duration().fromSec(2.0);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/plug_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/plug_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/plug_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -417,7 +417,7 @@
{
tf::Transform transform;
tf::TransformKDLToTF(controller_.endeffector_frame_, transform);
- tf::TransformTFToMsg(transform, current_frame_publisher_->msg_);
+ tf::transformTFToMsg(transform, current_frame_publisher_->msg_);
current_frame_publisher_->unlockAndPublish() ;
}
if (internal_state_publisher_->trylock())
@@ -449,7 +449,7 @@
return;
}
tf::Pose outlet;
- tf::PoseMsgToTF(outlet_in_root_.pose, outlet);
+ tf::poseMsgToTF(outlet_in_root_.pose, outlet);
controller_.outlet_pt_(0) = outlet.getOrigin().x();
controller_.outlet_pt_(1) = outlet.getOrigin().y();
@@ -490,7 +490,7 @@
}
tf::Transform tool_offset;
- tf::PoseMsgToTF(tool_offset_msg.pose, tool_offset);
+ tf::poseMsgToTF(tool_offset_msg.pose, tool_offset);
controller_.setToolOffset(tool_offset);
return true;
}
Modified: pkg/trunk/demos/plug_in/src/servo.cpp
===================================================================
--- pkg/trunk/demos/plug_in/src/servo.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/demos/plug_in/src/servo.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -84,7 +84,7 @@
}
tf::Pose viz_offset;
- tf::PoseMsgToTF(viz_offset_msg.pose, viz_offset);
+ tf::poseMsgToTF(viz_offset_msg.pose, viz_offset);
static double last_standoff = 1.0e10;
double standoff = std::max(MIN_STANDOFF, viz_offset.getOrigin().length() * 2.5/4.0);
Modified: pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/drivers/laser/laser_scan_annotator/src/laser_scan_annotator_node.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -98,7 +98,7 @@
catch(tf::TransformException e) {
continue;
}
- tf::PoseStampedTFToMsg(transform, scan_annotated.poses[i]) ;
+ tf::poseStampedTFToMsg(transform, scan_annotated.poses[i]) ;
}
publish("scan_annotated", scan_annotated);
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_fake_localization.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -105,7 +105,7 @@
// Build Transform Message
tf::Transform mytf;
- tf::TransformMsgToTF(body.pose,mytf);
+ tf::transformMsgToTF(body.pose,mytf);
if (publish_transform_)
m_tfServer->sendTransform(mytf,m_currentPos.header.stamp,"base","map");
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_pose_stamped.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -138,7 +138,7 @@
// Define our starting frame
tf::Quaternion rot_phasespace ;
- tf::QuaternionMsgToTF(cur_body.pose.rotation, rot_phasespace) ;
+ tf::quaternionMsgToTF(cur_body.pose.rotation, rot_phasespace) ;
tf::Point trans_phasespace(cur_body.pose.translation.x*scale_trans_[0],
cur_body.pose.translation.y*scale_trans_[1],
cur_body.pose.translation.z*scale_trans_[2]) ;
@@ -152,8 +152,8 @@
pose_msg.header.stamp = ros::Time() ;
pose_msg.header.frame_id = frame_id_ ;
- tf::PointTFToMsg(pose_result.getOrigin(), pose_msg.pose.position) ;
- tf::QuaternionTFToMsg(pose_result.getRotation(), pose_msg.pose.orientation) ;
+ tf::pointTFToMsg(pose_result.getOrigin(), pose_msg.pose.position) ;
+ tf::quaternionTFToMsg(pose_result.getRotation(), pose_msg.pose.orientation) ;
pose_msg.header.stamp = ros::Time::now() - ros::Duration(.5) ;
publish("cmd", pose_msg) ;
Modified: pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_tongs.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_tongs.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/drivers/robot/pr2/pr2_phase_space/src/phase_space_tongs.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -109,12 +109,12 @@
if (snapshot_.bodies[i].id == left_id_)
{
left_found = true ;
- tf::TransformMsgToTF(snapshot_.bodies[i].pose, left) ;
+ tf::transformMsgToTF(snapshot_.bodies[i].pose, left) ;
}
if (snapshot_.bodies[i].id == right_id_)
{
right_found = true ;
- tf::TransformMsgToTF(snapshot_.bodies[i].pose, right) ;
+ tf::transformMsgToTF(snapshot_.bodies[i].pose, right) ;
}
}
@@ -135,7 +135,7 @@
tf::Stamped<tf::Pose> tf_pose(left, snapshot_.header.stamp, frame_id_) ;
robot_msgs::PoseStamped pose_msg ;
- tf::PoseStampedTFToMsg(tf_pose, pose_msg) ;
+ tf::poseStampedTFToMsg(tf_pose, pose_msg) ;
node_->publish("tong_spacing", tong_spacing) ;
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_grasp_handle.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_grasp_handle.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_grasp_handle.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -99,7 +99,7 @@
gripper_pose.setOrigin( Vector3(handle(0) + (normal(0) * -0.15), handle(1) + (normal(1) * -0.15), handle(2) + (normal(2) * -0.15)));
gripper_pose.setRotation( Quaternion(getVectorAngle(x_axis, normal), 0, M_PI/2.0) );
gripper_pose.stamp_ = Time::now();
- PoseStampedTFToMsg(gripper_pose, req_moveto.pose);
+ poseStampedTFToMsg(gripper_pose, req_moveto.pose);
ROS_INFO("GraspHandleAction: move in front of handle");
if (!ros::service::call("r_arm_constraint_cartesian_trajectory_controller/move_to", req_moveto, res_moveto)){
@@ -119,7 +119,7 @@
gripper_pose.setOrigin( Vector3(handle(0) + (normal(0) * 0.05 ), handle(1) + (normal(1) * 0.05), handle(2) + (normal(2) * 0.05)));
gripper_pose.setRotation( Quaternion(getVectorAngle(x_axis, normal), 0, M_PI/2.0) );
gripper_pose.stamp_ = Time::now();
- PoseStampedTFToMsg(gripper_pose, req_moveto.pose);
+ poseStampedTFToMsg(gripper_pose, req_moveto.pose);
//req_moveto.tolerance.vel.x = 0.1;
//req_moveto.tolerance.vel.y = 0.1;
//req_moveto.tolerance.vel.z = 0.1;
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_push_door.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_push_door.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_push_door.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -122,7 +122,7 @@
// define griper pose
gripper_pose = getGripperPose(goal_tr, angle, push_dist);
gripper_pose.stamp_ = Time::now();
- PoseStampedTFToMsg(gripper_pose, gripper_pose_msg);
+ poseStampedTFToMsg(gripper_pose, gripper_pose_msg);
pose_pub_.publish(gripper_pose_msg);
// increase angle when pose error is small enough
@@ -138,7 +138,7 @@
void PushDoorAction::poseCallback(const PoseConstPtr& pose)
{
boost::mutex::scoped_lock lock(pose_mutex_);
- PoseStampedMsgToTF(*pose, pose_state_);
+ poseStampedMsgToTF(*pose, pose_state_);
pose_state_received_ = true;
}
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_release_handle.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_release_handle.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_release_handle.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -101,7 +101,7 @@
// move gripper away from the door
Pose offset(Quaternion(0,0,0), Vector3(-0.2,0,0));
Pose gripper_goal = gripper_pose_ * offset;
- PoseStampedTFToMsg(Stamped<Pose>(gripper_goal, Time::now(), gripper_pose_.frame_id_), req_moveto.pose);
+ poseStampedTFToMsg(Stamped<Pose>(gripper_goal, Time::now(), gripper_pose_.frame_id_), req_moveto.pose);
ROS_INFO("ReleaseHandleAction: move gripper away from door ");
if (!ros::service::call("r_arm_constraint_cartesian_trajectory_controller/move_to", req_moveto, res_moveto)){
@@ -123,7 +123,7 @@
void ReleaseHandleAction::poseCallback(const PoseConstPtr& pose)
{
boost::mutex::scoped_lock lock(pose_mutex_);
- PoseStampedMsgToTF(*pose, gripper_pose_);
+ poseStampedMsgToTF(*pose, gripper_pose_);
pose_received_ = true;
}
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_touch_door.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_touch_door.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_touch_door.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -99,7 +99,7 @@
//}
Stamped<Pose> gripper_pose = getGripperPose(goal_tr, getNearestDoorAngle(shoulder_pose, goal_tr, 0.75, touch_dist), touch_dist);
gripper_pose.stamp_ = Time::now();
- PoseStampedTFToMsg(gripper_pose, req_moveto.pose);
+ poseStampedTFToMsg(gripper_pose, req_moveto.pose);
//req_moveto.tolerance.vel.x = 0.1;
//req_moveto.tolerance.vel.y = 0.1;
//req_moveto.tolerance.vel.z = 0.1;
Modified: pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -157,7 +157,7 @@
// approach door
robot_msgs::PoseStamped goal_msg;
- tf::PoseStampedTFToMsg(getRobotPose(res_detect_door, -0.6), goal_msg);
+ tf::poseStampedTFToMsg(getRobotPose(res_detect_door, -0.6), goal_msg);
cout << "move to pose " << goal_msg.pose.position.x << ", " << goal_msg.pose.position.y << ", "<< goal_msg.pose.position.z << endl;
switchlist.start_controllers.clear(); switchlist.stop_controllers.clear();
if (switch_controllers.execute(switchlist, empty, timeout_short) != robot_actions::SUCCESS) return -1;
Modified: pkg/trunk/highlevel/doors/doors_core/test/test_planner.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/test/test_planner.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/doors/doors_core/test/test_planner.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -144,7 +144,7 @@
// approach door
robot_msgs::PoseStamped goal_msg;
- tf::PoseStampedTFToMsg(getRobotPose(door, -0.6), goal_msg);
+ tf::poseStampedTFToMsg(getRobotPose(door, -0.6), goal_msg);
cout << "move to pose " << goal_msg.pose.position.x << ", " << goal_msg.pose.position.y << ", "<< goal_msg.pose.position.z << endl;
switchlist.start_controllers.clear(); switchlist.stop_controllers.clear();
if (switch_controllers.execute(switchlist, empty, timeout_short) != robot_actions::SUCCESS) return -1;
@@ -258,7 +258,7 @@
tf::Stamped<tf::Pose> handle_pose = getHandlePose(tmp_door,-1);
robot_msgs::PoseStamped handle_msg;
handle_pose.stamp_ = ros::Time::now();
- PoseStampedTFToMsg(handle_pose, handle_msg);
+ poseStampedTFToMsg(handle_pose, handle_msg);
int32_t feedback_move_arm;
pr2_robot_actions::MoveArmGoal goal_move_arm;
Modified: pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -149,7 +149,7 @@
g_stopped_forcing_ = ros::Time::now();
}
-void PoseTFToMsg(const tf::Pose &p, robot_msgs::Twist &t)
+void poseTFToMsg(const tf::Pose &p, robot_msgs::Twist &t)
{
t.vel.x = p.getOrigin().x();
t.vel.y = p.getOrigin().y();
@@ -187,8 +187,8 @@
}
tf::Pose viz_offset;
- tf::PoseMsgToTF(viz_offset_msg.pose, viz_offset);
- PoseTFToMsg(viz_offset, state_msg.viz_offset);
+ tf::poseMsgToTF(viz_offset_msg.pose, viz_offset);
+ poseTFToMsg(viz_offset, state_msg.viz_offset);
// Deals with the per-outlet offsets
{
@@ -211,7 +211,7 @@
viz_offset_desi.getOrigin().setX(-standoff);
viz_offset_desi.getOrigin().setY(0.0);
viz_offset_desi.getOrigin().setZ(0.0);
- PoseTFToMsg(viz_offset.inverse() * viz_offset_desi, state_msg.viz_error);
+ poseTFToMsg(viz_offset.inverse() * viz_offset_desi, state_msg.viz_error);
mech_offset_desi_ = viz_offset.inverse() * viz_offset_desi * mech_offset_;
prev_state_ = g_state_;
Modified: pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in2.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in2.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/plugs/plugs_core/src/action_plug_in2.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -75,7 +75,7 @@
}
}
-void PoseTFToMsg(const tf::Pose &p, robot_msgs::Twist &t)
+void poseTFToMsg(const tf::Pose &p, robot_msgs::Twist &t)
{
t.vel.x = p.getOrigin().x();
t.vel.y = p.getOrigin().y();
@@ -83,7 +83,7 @@
btMatrix3x3(p.getRotation()).getEulerYPR(t.rot.x, t.rot.y, t.rot.z);
}
-void PoseMsgToTF(const robot_msgs::Twist &t, tf::Pose &p)
+void poseMsgToTF(const robot_msgs::Twist &t, tf::Pose &p)
{
p.getOrigin()[0] = t.vel.x;
p.getOrigin()[1] = t.vel.y;
@@ -252,7 +252,7 @@
tff_msg.mode.rot.x = 3;
tff_msg.mode.rot.y = 3;
tff_msg.mode.rot.z = 3;
- PoseTFToMsg(target, tff_msg.value);
+ poseTFToMsg(target, tff_msg.value);
node_.publish(arm_controller_ + "/command", tff_msg);
ros::Duration(1.0).sleep(); // Settle
}
@@ -276,7 +276,7 @@
tff_msg.mode.rot.x = 3;
tff_msg.mode.rot.y = 3;
tff_msg.mode.rot.z = 3;
- PoseTFToMsg(desi, tff_msg.value);
+ poseTFToMsg(desi, tff_msg.value);
tff_msg.value.vel.x = SPEED;
node_.publish(arm_controller_ + "/command", tff_msg);
@@ -345,7 +345,7 @@
tff_msg.mode.rot.x = 3;
tff_msg.mode.rot.y = 3;
tff_msg.mode.rot.z = 3;
- PoseTFToMsg(desi, tff_msg.value);
+ poseTFToMsg(desi, tff_msg.value);
tff_msg.value.vel.x = first_x - 0.03;
//tff_msg.value.vel.x = removal_speed;
node_.publish(arm_controller_ + "/command", tff_msg);
@@ -501,7 +501,7 @@
if (from_viz_lock_.try_lock())
{
//boost::mutex::scoped_lock(from_viz_lock_);
- tf::PoseStampedMsgToTF(viz_offset_msg, viz_offset_from_viz_);
+ tf::poseStampedMsgToTF(viz_offset_msg, viz_offset_from_viz_);
mech_offset_from_viz_ = mech_offset;
updated_from_viz_ = true;
from_viz_lock_.unlock();
@@ -517,7 +517,7 @@
if (from_c_lock_.try_lock())
{
- PoseMsgToTF(c_state_msg_.last_pose_meas, pose_from_mech_);
+ poseMsgToTF(c_state_msg_.last_pose_meas, pose_from_mech_);
from_c_lock_.unlock();
}
}
@@ -530,8 +530,8 @@
tff_msg_.header.stamp = msg->header.stamp;
tf::Pose viz_offset;
- tf::PoseMsgToTF(viz_offset_msg.pose, viz_offset);
- PoseTFToMsg(viz_offset, state_msg.viz_offset);
+ tf::poseMsgToTF(viz_offset_msg.pose, viz_offset);
+ poseTFToMsg(viz_offset, state_msg.viz_offset);
double standoff = std::max(MIN_STANDOFF, viz_offset.getOrigin().length() * 2.5/4.0);
// Computes the offset for movement
@@ -540,7 +540,7 @@
viz_offset_desi.getOrigin().setX(-standoff);
viz_offset_desi.getOrigin().setY(0.0);
viz_offset_desi.getOrigin().setZ(0.0);
- PoseTFToMsg(viz_offset.inverse() * viz_offset_desi, state_msg.viz_error);
+ poseTFToMsg(viz_offset.inverse() * viz_offset_desi, state_msg.viz_error);
mech_offset_desi_ = viz_offset.inverse() * viz_offset_desi * mech_offset_;
prev_state_ = g_state_;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_approach.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -137,14 +137,14 @@
// Determines the desired base position
tf::Pose coarse_outlet_pose;
- tf::PoseMsgToTF(coarse_outlet_pose_msg.pose, coarse_outlet_pose);
+ tf::poseMsgToTF(coarse_outlet_pose_msg.pose, coarse_outlet_pose);
tf::Pose desi_offset(tf::Quaternion(0,0,0), tf::Vector3(-0.5, 0.25, 0.0));
tf::Pose target = coarse_outlet_pose * desi_offset;
robot_msgs::PoseStamped target_msg;
target_msg.header.frame_id = coarse_outlet_pose_msg.header.frame_id;
- tf::PoseTFToMsg(target, target_msg.pose);
+ tf::poseTFToMsg(target, target_msg.pose);
// Executes move base
if (move_base_local.execute(target_msg, target_msg, Duration(500.0)) != robot_actions::SUCCESS) return -4;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -175,14 +175,14 @@
// Determines the desired base position
tf::Pose coarse_outlet_pose;
- tf::PoseMsgToTF(coarse_outlet_pose_msg.pose, coarse_outlet_pose);
+ tf::poseMsgToTF(coarse_outlet_pose_msg.pose, coarse_outlet_pose);
tf::Pose desi_offset(tf::Quaternion(0,0,0), tf::Vector3(-0.5, 0.25, 0.0));
tf::Pose target = coarse_outlet_pose * desi_offset;
robot_msgs::PoseStamped target_msg;
target_msg.header.frame_id = coarse_outlet_pose_msg.header.frame_id;
- tf::PoseTFToMsg(target, target_msg.pose);
+ tf::poseTFToMsg(target, target_msg.pose);
// Executes move base
if (move_base_local.execute(target_msg, target_msg, Duration(500.0)) != robot_actions::SUCCESS) return -50;
Modified: pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/plugs/plugs_core/test/test_executive_outlet_coarse.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -73,13 +73,13 @@
tf::Pose tf_pose;
robot_msgs::Pose final_pose;
- tf::PoseMsgToTF(outletPose,tf_pose);
+ tf::poseMsgToTF(outletPose,tf_pose);
tf::Point point(-value,0,0);
tf::Point new_origin = tf_pose*point;
tf_pose.setOrigin(new_origin);
- tf::PoseTFToMsg(tf_pose,final_pose);
+ tf::poseTFToMsg(tf_pose,final_pose);
return final_pose;
}
Modified: pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/plugs/plugs_functions/src/plugs_functions.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -42,13 +42,13 @@
tf::Pose tf_pose;
robot_msgs::Pose final_pose;
- tf::PoseMsgToTF(outletPose,tf_pose);
+ tf::poseMsgToTF(outletPose,tf_pose);
tf::Point point(-value,0,0);
tf::Point new_origin = tf_pose*point;
tf_pose.setOrigin(new_origin);
- tf::PoseTFToMsg(tf_pose,final_pose);
+ tf::poseTFToMsg(tf_pose,final_pose);
return final_pose;
}
Modified: pkg/trunk/highlevel/writing/writing_test/src/test_move_to_helper.cpp
===================================================================
--- pkg/trunk/highlevel/writing/writing_test/src/test_move_to_helper.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/highlevel/writing/writing_test/src/test_move_to_helper.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -113,14 +113,14 @@
// Determines the desired base position
//tf::Pose helper_pose;
- //tf::PoseMsgToTF(find_helper_pose_msg.pose, helper_pose);
+ //tf::poseMsgToTF(find_helper_pose_msg.pose, helper_pose);
//tf::Pose desi_offset(tf::Quaternion(0,0,0), tf::Vector3(-1.5, 0.0, 0.0));
//tf::Pose target = coarse_outlet_pose * desi_offset;
//robot_msgs::PoseStamped target_msg;
//target_msg.header.frame_id = find_helper_pose_msg.header.frame_id;
- //tf::PoseTFToMsg(target, target_msg.pose);
+ //tf::poseTFToMsg(target, target_msg.pose);
// Executes move base
if (start_tilt_laser.execute(empty, empty, Duration(20.0)) != robot_actions::SUCCESS) return -1;
Modified: pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/motion_planning/planning_environment/src/kinematic_state_constraint_evaluator.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -122,7 +122,7 @@
m_pc = pc;
tf::Pose pose;
- tf::PoseMsgToTF(m_pc.pose.pose, pose);
+ tf::poseMsgToTF(m_pc.pose.pose, pose);
pose.getBasis().getEulerYPR(m_yaw, m_pitch, m_roll);
m_x = pose.getOrigin().x();
m_y = pose.getOrigin().y();
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/src/pr2_arm_node.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/src/pr2_arm_node.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/src/pr2_arm_node.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -344,7 +344,7 @@
req.value.goal_constraints[i].y = pose_goals[i].position.y;
req.value.goal_constraints[i].z = pose_goals[i].position.z;
- tf::PoseMsgToTF(pose_goals[i],tf_pose);
+ tf::poseMsgToTF(pose_goals[i],tf_pose);
btMatrix3x3 mat = tf_pose.getBasis();
mat.getEulerZYX(yaw,pitch,roll);
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/src/sbpl_arm_planner_node.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -269,7 +269,7 @@
sbpl_goal[i][1] = goals[i].pose.pose.position.y;// - torso_arm_offset_y_;
sbpl_goal[i][2] = goals[i].pose.pose.position.z;// - torso_arm_offset_z_;
- tf::PoseMsgToTF(goals[i].pose.pose, tf_pose);
+ tf::poseMsgToTF(goals[i].pose.pose, tf_pose);
btMatrix3x3 mat = tf_pose.getBasis();
mat.getEulerZYX(yaw,pitch,roll);
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -441,7 +441,7 @@
robot_msgs::PoseStamped gripper_msg;
gripper_pose.stamp_ = ros::Time::now();
- PoseStampedTFToMsg(gripper_pose, gripper_msg);
+ poseStampedTFToMsg(gripper_pose, gripper_msg);
pr2_ik::PoseCmd cmd;
cmd.pose = gripper_msg.pose;
@@ -518,7 +518,7 @@
robot_msgs::PoseStamped handle_msg;
robot_msgs::Point32 handle_position;
global_handle_position_tf.stamp_ = ros::Time::now();
- PoseStampedTFToMsg(global_handle_position_tf, handle_msg);
+ poseStampedTFToMsg(global_handle_position_tf, handle_msg);
//get shoulder in global frame
global_shoulder_position.x = waypoint.positions[0] + (door_env_.shoulder.x*cos(waypoint.positions[2])-door_env_.shoulder.y*sin(waypoint.positions[2]));
global_shoulder_position.y = waypoint.positions[1] + (door_env_.shoulder.x*sin(waypoint.positions[2])+door_env_.shoulder.y*cos(waypoint.positions[2]));
@@ -585,7 +585,7 @@
double yaw = getDoorAngle(result);
tf::Stamped<tf::Pose> gripper_pose = getGlobalHandlePosition(door_env_.door,angle);
gripper_pose.stamp_ = ros::Time::now();
- PoseStampedTFToMsg(gripper_pose, gripper_msg);
+ poseStampedTFToMsg(gripper_pose, gripper_msg);
visualization_msgs::Marker marker;
marker.header.frame_id = gripper_msg.header.frame_id;
marker.header.stamp = ros::Time();
Modified: pkg/trunk/nav/people_aware_nav/src/is_person_on_path.cpp
===================================================================
--- pkg/trunk/nav/people_aware_nav/src/is_person_on_path.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/nav/people_aware_nav/src/is_person_on_path.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -154,7 +154,7 @@
// Convert the path and the person to the current time. If either is stale (too old for TF), mark them as unusable and return false.
(*current_time) = (person_pos_.header.stamp > path_.header.stamp) ? person_pos_.header.stamp : path_.header.stamp;
tf::Point pt;
- tf::PointMsgToTF(person_pos_.pos, pt);
+ tf::pointMsgToTF(person_pos_.pos, pt);
tf::Stamped<tf::Point> t_person_tf_stamped_point(pt, person_pos_.header.stamp, person_pos_.header.frame_id);
try {
tf_->transformPoint(fixed_frame_, *current_time, t_person_tf_stamped_point, fixed_frame_, t_person_tf_stamped_point);
Modified: pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp
===================================================================
--- pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/nav/people_aware_nav/src/move_base_constrained.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -137,7 +137,7 @@
}
robot_msgs::PoseStamped start;
- tf::PoseStampedTFToMsg(global_pose, start);
+ tf::poseStampedTFToMsg(global_pose, start);
std::vector<robot_msgs::PoseStamped> global_plan;
bool valid_plan = planner_->makePlan(start, goal, global_plan);
@@ -196,7 +196,7 @@
// Transform constrained goal into posestamped
goal_.header = goal.header;
- tf::PoseTFToMsg(tf::Pose(btQuaternion(goal.th, 0, 0),
+ tf::poseTFToMsg(tf::Pose(btQuaternion(goal.th, 0, 0),
btVector3(goal.x, goal.y, goal.z)),
goal_.pose);
@@ -217,7 +217,7 @@
//update feedback to correspond to our current position
tf::Stamped<tf::Pose> global_pose;
getRobotPose(goal_.header.frame_id, global_pose);
- tf::PoseStampedTFToMsg(global_pose, feedback);
+ tf::poseStampedTFToMsg(global_pose, feedback);
//push the feedback out
update(feedback);
@@ -350,7 +350,7 @@
}
- PoseStampedTFToMsg(rotate_goal, rotate_goal_msg);
+ poseStampedTFToMsg(rotate_goal, rotate_goal_msg);
global_plan_.clear();
global_plan_.push_back(rotate_goal_msg);
valid_plan_ = true;
Modified: pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp
===================================================================
--- pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/nav/teleop_base/src/ground_truth_controller.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -117,7 +117,7 @@
tf::Transform ground_truth_pose ;
- tf::PoseMsgToTF(m_ground_truth_.pos, ground_truth_pose) ;
+ tf::poseMsgToTF(m_ground_truth_.pos, ground_truth_pose) ;
//! \todo Compute yaw angle in a more stable way
double yaw,pitch,roll ;
Modified: pkg/trunk/nav/visual_nav/src/ros_visual_nav.cpp
===================================================================
--- pkg/trunk/nav/visual_nav/src/ros_visual_nav.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/nav/visual_nav/src/ros_visual_nav.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -438,7 +438,7 @@
goal.pose.position.x = exit_point_.x;
goal.pose.position.y = exit_point_.y;
- tf::QuaternionTFToMsg(tf::Quaternion(exit_point_.theta, 0, 0), goal.pose.orientation);
+ tf::quaternionTFToMsg(tf::Quaternion(exit_point_.theta, 0, 0), goal.pose.orientation);
goal.header.frame_id = "vslam";
tf_listener_.transformPose(odom_frame_, goal, odom_goal);
Modified: pkg/trunk/nav/wavefront/src/cli.cpp
===================================================================
--- pkg/trunk/nav/wavefront/src/cli.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/nav/wavefront/src/cli.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -17,7 +17,7 @@
: ros::Node("wavefront_cli"), state(WF_IDLE)
{
tf::Stamped<tf::Pose> p = tf::Stamped<tf::Pose>(tf::Pose(tf::Quaternion(th, 0.0, 0.0), tf::Point(x, y, 0.0)), ros::Time::now(), "map");
- tf::PoseStampedTFToMsg(p, wf_goal);
+ tf::poseStampedTFToMsg(p, wf_goal);
subscribe("state", wf_state, &WavefrontCLI::state_cb, 1);
advertise("goal", wf_goal, &WavefrontCLI::goal_subscriber_callback, 1);
Modified: pkg/trunk/nav/wavefront/src/wavefront_node.cpp
===================================================================
--- pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/nav/wavefront/src/wavefront_node.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -385,7 +385,7 @@
this->enable = 1;
if(this->enable){
- tf::PoseStampedMsgToTF(goalMsg, this->goalPose_);
+ tf::poseStampedMsgToTF(goalMsg, this->goalPose_);
// Populate goal data
@@ -413,7 +413,7 @@
}
robot_msgs::PoseStamped pose_msg;
- tf::PoseStampedTFToMsg(global_pose_, pose_msg);
+ tf::poseStampedTFToMsg(global_pose_, pose_msg);
// Fill out and publish response
this->pstate.feedback = pose_msg;
@@ -760,9 +760,9 @@
this->pstate.status.value = this->pstate.status.SUCCESS;
robot_msgs::PoseStamped pose_out;
- tf::PoseStampedTFToMsg(global_pose_, pose_out);
+ tf::poseStampedTFToMsg(global_pose_, pose_out);
this->pstate.feedback = pose_out;
- tf::PoseStampedTFToMsg(this->goalPose_, pose_out);
+ tf::poseStampedTFToMsg(this->goalPose_, pose_out);
this->pstate.goal = pose_out;
publish("state",this->pstate);
Modified: pkg/trunk/sandbox/descriptors_3d/.build_version
===================================================================
--- pkg/trunk/sandbox/descriptors_3d/.build_version 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/sandbox/descriptors_3d/.build_version 2009-07-02 21:27:56 UTC (rev 18230)
@@ -1 +1 @@
-:
+https://personalrobots.svn.sourceforge.net/svnroot/personalrobots/pkg/trunk/sandbox/descriptors_3d:18221
Modified: pkg/trunk/sandbox/descriptors_3d/.rosgcov_files
===================================================================
--- pkg/trunk/sandbox/descriptors_3d/.rosgcov_files 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/sandbox/descriptors_3d/.rosgcov_files 2009-07-02 21:27:56 UTC (rev 18230)
@@ -1 +1 @@
-/u/dmunoz/ros/ros-pkg/sandbox/descriptors_3d src/descriptors_3d.cpp
+/home/tfoote/ros/ros-pkg/sandbox/descriptors_3d src/descriptors_3d.cpp
Modified: pkg/trunk/sandbox/labeled_object_detector/src/planar_object_detector.cpp
===================================================================
--- pkg/trunk/sandbox/labeled_object_detector/src/planar_object_detector.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/sandbox/labeled_object_detector/src/planar_object_detector.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -529,19 +529,19 @@
tf::Point pt(0,0,0);
robot_msgs::Point pt_msg;
- tf::PointTFToMsg(pt, pt_msg);
+ tf::pointTFToMsg(pt, pt_msg);
marker.points.push_back(pt_msg);
tf::Point pt2(1,0,0);
- tf::PointTFToMsg(pt2, pt_msg);
+ tf::pointTFToMsg(pt2, pt_msg);
marker.points.push_back(pt_msg);
tf::Point pt3(1,1,0);
- tf::PointTFToMsg(pt3, pt_msg);
+ tf::pointTFToMsg(pt3, pt_msg);
marker.points.push_back(pt_msg);
tf::Point pt4(0,1,0);
- tf::PointTFToMsg(pt4, pt_msg);
+ tf::pointTFToMsg(pt4, pt_msg);
marker.points.push_back(pt_msg);
@@ -581,19 +581,19 @@
tf::Point pt(x+0,y+0,z+0);
robot_msgs::Point pt_msg;
- tf::PointTFToMsg(pt, pt_msg);
+ tf::pointTFToMsg(pt, pt_msg);
marker.points.push_back(pt_msg);
tf::Point pt2(x+1,y+0,z+0);
- tf::PointTFToMsg(pt2, pt_msg);
+ tf::pointTFToMsg(pt2, pt_msg);
marker.points.push_back(pt_msg);
tf::Point pt3(x+1,y+1,z+0);
- tf::PointTFToMsg(pt3, pt_msg);
+ tf::pointTFToMsg(pt3, pt_msg);
marker.points.push_back(pt_msg);
tf::Point pt4(0,1,0);
- tf::PointTFToMsg(pt4, pt_msg);
+ tf::pointTFToMsg(pt4, pt_msg);
marker.points.push_back(pt_msg);
Modified: pkg/trunk/sandbox/poseviz/src/poseviz.cpp
===================================================================
--- pkg/trunk/sandbox/poseviz/src/poseviz.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/sandbox/poseviz/src/poseviz.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -28,7 +28,7 @@
{
// Record the current pose
tf::Pose tf_pose ;
- tf::PoseMsgToTF(msg->pose, tf_pose) ;
+ tf::poseMsgToTF(msg->pose, tf_pose) ;
// Initialize the marker message
visualization_msgs::Marker marker ;
@@ -56,7 +56,7 @@
// Publish the Y axis
btQuaternion x_to_y(btVector3(0.0, 0.0, 1.0), M_PI/2) ;
- tf::PoseTFToMsg( tf_pose*btTransform(x_to_y), marker.pose) ;
+ tf::poseTFToMsg( tf_pose*btTransform(x_to_y), marker.pose) ;
marker.id = 1 ;
marker.color.r = 0.0 ;
marker.color.g = 1.0 ;
@@ -67,7 +67,7 @@
// Publish the Z axis
btQuaternion x_to_z(btVector3(0.0,-1.0, 0.0), M_PI/2) ;
- tf::PoseTFToMsg( tf_pose*btTransform(x_to_z), marker.pose) ;
+ tf::poseTFToMsg( tf_pose*btTransform(x_to_z), marker.pose) ;
marker.id = 2 ;
marker.color.r = 0.0 ;
marker.color.g = 0.0 ;
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -344,7 +344,7 @@
return;
}
transformer_.lookupTransform("base_footprint","odom", ros::Time(), tmp);
- PoseTFToMsg(tmp, estimate.pose);
+ poseTFToMsg(tmp, estimate.pose);
// header
estimate.header.stamp = tmp.stamp_;
Modified: pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp
===================================================================
--- pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/stacks/estimation/robot_pose_ekf/src/odom_estimation_node.cpp 2009-07-02 21:27:56 UTC (rev 18230)
@@ -201,7 +201,7 @@
boost::mutex::scoped_lock lock(imu_mutex_);
imu_stamp_ = imu->header.stamp;
imu_time_ = Time::now();
- PoseMsgToTF(imu->pos, imu_meas_);
+ poseMsgToTF(imu->pos, imu_meas_);
my_filter_.addMeasurement(Stamped<Transform>(imu_meas_, imu_stamp_, "imu", "base_footprint"));
// activate imu
@@ -245,7 +245,7 @@
return;
}
robot_state_.lookupTransform("stereo_link","base_link", vo_stamp_, camera_base_);
- PoseMsgToTF(vo->pose, vo_meas_);
+ poseMsgToTF(vo->pose, vo_meas_);
// initialize
if (!vo_active_ && !vo_initializing_){
Modified: pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h
===================================================================
--- pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-07-02 21:24:43 UTC (rev 18229)
+++ pkg/trunk/stacks/geometry/tf/include/tf/transform_datatypes.h 2009-07-02 21:27:56 UTC (rev 18230)
@@ -83,7 +83,7 @@
/** \brief convert Quaternion msg to Quaternion */
-static inline void QuaternionMsgToTF(const robot_msgs::Quaternion& msg, Quaternion& bt)
+static inline void quaternionMsgToTF(const robot_msgs::Quaternion& msg, Quaternion& bt)
{
bt = Quaternion(msg.x, msg.y, msg.z, msg.w);
if (fabs(bt.length2() - 1 ) > QUATERNION_TOLERANCE)
@@ -93,7 +93,7 @@
}
};
/** \brief convert Quaternion to Quaternion msg*/
-static inline void QuaternionTFToMsg(const Quaternion& bt, robot_msgs::Quaternion& msg)
+static inline void quaternionTFToMsg(const Quaternion& bt, robot_msgs::Quaternion& msg)
{
if (fabs(bt.length2() - 1 ) > QUATERNION_TOLERANCE)
{
@@ -109,65 +109,65 @@
};
/** \brief convert QuaternionStamped msg to Stamped<Quaternion> */
-static inline void QuaternionStampedMsgToTF(const robot_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
-{QuaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+static inline void quaternionStampedMsgToTF(const robot_msgs::QuaternionStamped & msg, Stamped<Quaternion>& bt)
+{quaternionMsgToTF(msg.quaternion, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Quaternion> to QuaternionStamped msg*/
-static inline void QuaternionStampedTFToMsg(const Stamped<Quaternion>& bt, robot_msgs::QuaternionStamped & msg)
-{QuaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+static inline void quaternionStampedTFToMsg(const Stamped<Quaternion>& bt, robot_msgs::QuaternionStamped & msg)
+{quaternionTFToMsg(bt, msg.quaternion); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Vector3 msg to Vector3 */
-static inline void Vector3MsgToTF(const robot_msgs::Vector3& msg_v, Vector3& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
+static inline void vector3MsgToTF(const robot_msgs::Vector3& msg_v, Vector3& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
/** \brief convert Vector3 to Vector3 msg*/
-static inline void Vector3TFToMsg(const Vector3& bt_v, robot_msgs::Vector3& msg_v) {msg_v.x = bt_v.x(); msg_v.y = bt_v.y(); msg_v.z = bt_v.z();};
+static inline void vector3TFToMsg(const Vector3& bt_v, robot_msgs::Vector3& msg_v) {msg_v.x = bt_v.x(); msg_v.y = bt_v.y(); msg_v.z = bt_v.z();};
/** \brief convert Vector3Stamped msg to Stamped<Vector3> */
-static inline void Vector3StampedMsgToTF(const robot_msgs::Vector3Stamped & msg, Stamped<Vector3>& bt)
-{Vector3MsgToTF(msg.vector, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+static inline void vector3StampedMsgToTF(const robot_msgs::Vector3Stamped & msg, Stamped<Vector3>& bt)
+{vector3MsgToTF(msg.vector, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Vector3> to Vector3Stamped msg*/
-static inline void Vector3StampedTFToMsg(const Stamped<Vector3>& bt, robot_msgs::Vector3Stamped & msg)
-{Vector3TFToMsg(bt, msg.vector); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+static inline void vector3StampedTFToMsg(const Stamped<Vector3>& bt, robot_msgs::Vector3Stamped & msg)
+{vector3TFToMsg(bt, msg.vector); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
/** \brief convert Point msg to Point */
-static inline void PointMsgToTF(const robot_msgs::Point& msg_v, Point& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
+static inline void pointMsgToTF(const robot_msgs::Point& msg_v, Point& bt_v) {bt_v = Vector3(msg_v.x, msg_v.y, msg_v.z);};
/** \brief convert Point to Point msg*/
-static inline void PointTFToMsg(const Point& bt_v, robot_msgs::Point& msg_v) {msg_v.x = bt_v.x(); msg_v.y = bt_v.y(); msg_v.z = bt_v.z();};
+static inline void pointTFToMsg(const Point& bt_v, robot_msgs::Point& msg_v) {msg_v.x = bt_v.x(); msg_v.y = bt_v.y(); msg_v.z = bt_v.z();};
/** \brief convert PointStamped msg to Stamped<Point> */
-static inline void PointStampedMsgToTF(const robot_msgs::PointStamped & msg, Stamped<Point>& bt)
-{PointMsgToTF(msg.point, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
+static inline void pointStampedMsgToTF(const robot_msgs::PointStamped & msg, Stamped<Point>& bt)
+{pointMsgToTF(msg.point, bt); bt.stamp_ = msg.header.stamp; bt.frame_id_ = msg.header.frame_id;};
/** \brief convert Stamped<Point> to PointStamped msg*/
-static inline void PointStampedTFToMsg(const Stamped<Point>& bt, robot_msgs::PointStamped & msg)
-{PointTFToMsg(bt, msg.point); msg.header.stamp = bt.stamp_; msg.header.frame_id = bt.frame_id_;};
+static inline void pointStampedTFToMsg(const Stamped<Point>& bt, robot...
[truncated message content] |