|
From: <sac...@us...> - 2009-06-18 10:06:45
|
Revision: 17279
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17279&view=rev
Author: sachinchitta
Date: 2009-06-18 10:06:30 +0000 (Thu, 18 Jun 2009)
Log Message:
-----------
moved JointTraj and JointTrajPoint messages from robot_msgs to manipulation_msgs
Modified Paths:
--------------
pkg/trunk/calibration/auto_arm_commander/manifest.xml
pkg/trunk/calibration/auto_arm_commander/src/auto_arm_commander/arm_commander.py
pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander.py
pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander_original.py
pkg/trunk/calibration/kinematic_calibration/src/kinematic_calibration/arm_commander.py
pkg/trunk/calibration/optical_flag_calibration/manifest.xml
pkg/trunk/calibration/optical_flag_calibration/scripts/flag_tester.py
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/scripts/tuckarm.py
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/srv/GraspPointSrv.srv
pkg/trunk/controllers/pr2_mechanism_controllers/srv/TrajectoryStart.srv
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_joint_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_whole_body_controller.cpp
pkg/trunk/demos/plug_in/move_to_pickup.py
pkg/trunk/demos/tabletop_manipulation/scripts/tuckarm.py
pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h
pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
pkg/trunk/highlevel/move_arm/include/move_arm/move_arm.h
pkg/trunk/highlevel/move_arm/src/move_arm.cpp
pkg/trunk/highlevel/plugs/plugs_core/include/plugs_core/action_untuck_arms.h
pkg/trunk/highlevel/safety/safety_core/include/safety_core/action_tuck_arms.h
pkg/trunk/motion_planning/mpglue/include/mpglue/plan.h
pkg/trunk/motion_planning/mpglue/manifest.xml
pkg/trunk/motion_planning/mpglue/src/plan.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/plan_kinematic_path.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_replan_to_state.cpp
pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/test_path_execution.cpp
pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/include/sbpl_arm_executive/pr2_arm_node.h
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/CheckPathSrv.srv
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/PlanPathSrv.srv
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h
pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/manifest.xml
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/src/sbpl_planner_node.cpp
pkg/trunk/motion_planning/planning_research/sbpl_planner_node/srv/PlanPathSrv.srv
pkg/trunk/robot_descriptions/pr2/pr2_default_controllers/scripts/tuckarm.py
pkg/trunk/util/pr2_ik/include/pr2_ik/pr2_ik_controller.h
pkg/trunk/util/pr2_ik/include/pr2_ik/pr2_ik_node.h
pkg/trunk/util/pr2_ik/src/pr2_ik_controller.cpp
Added Paths:
-----------
pkg/trunk/common/manipulation_msgs/msg/JointTraj.msg
pkg/trunk/common/manipulation_msgs/msg/JointTrajPoint.msg
Removed Paths:
-------------
pkg/trunk/common/robot_msgs/msg/JointTraj.msg
pkg/trunk/common/robot_msgs/msg/JointTrajPoint.msg
pkg/trunk/common/robot_srvs/srv/IKService.srv
Modified: pkg/trunk/calibration/auto_arm_commander/manifest.xml
===================================================================
--- pkg/trunk/calibration/auto_arm_commander/manifest.xml 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/auto_arm_commander/manifest.xml 2009-06-18 10:06:30 UTC (rev 17279)
@@ -10,6 +10,7 @@
<depend package="pr2_mechanism_controllers" />
<depend package="std_msgs" />
<depend package="robot_msgs" />
+ <depend package="manipulation_msgs" />
</package>
Modified: pkg/trunk/calibration/auto_arm_commander/src/auto_arm_commander/arm_commander.py
===================================================================
--- pkg/trunk/calibration/auto_arm_commander/src/auto_arm_commander/arm_commander.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/auto_arm_commander/src/auto_arm_commander/arm_commander.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -41,8 +41,8 @@
from pr2_mechanism_controllers.srv import *
#from pr2_mechanism_controllers.msg import
from robot_msgs.msg import *
+from manipulation_msgs.msg import *
-
class ArmCommander() :
def __init__(self, arm_controller_name):
print "Initializing Object"
Modified: pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander.py
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -11,6 +11,7 @@
from robot_msgs.msg import *
from mechanism_msgs.msg import MechanismState
from kinematic_calibration.msg import *
+from manipulation_msgs.msg import *
arm_mapping = [ ]
headers = [ ]
Modified: pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander_original.py
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander_original.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/kinematic_calibration/scripts/auto_arm_commander_original.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -11,6 +11,7 @@
from robot_msgs.msg import *
from mechanism_msgs.msg import MechanismState
from kinematic_calibration.msg import *
+from manipulation_msgs.msg import *
traj_actuator_names = ['r_shoulder_pan_motor',
'r_shoulder_lift_motor',
Modified: pkg/trunk/calibration/kinematic_calibration/src/kinematic_calibration/arm_commander.py
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/src/kinematic_calibration/arm_commander.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/kinematic_calibration/src/kinematic_calibration/arm_commander.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -41,6 +41,7 @@
from pr2_mechanism_controllers.srv import *
#from pr2_mechanism_controllers.msg import
from robot_msgs.msg import *
+from manipulation_msgs.msg import *
class ArmCommander() :
Modified: pkg/trunk/calibration/optical_flag_calibration/manifest.xml
===================================================================
--- pkg/trunk/calibration/optical_flag_calibration/manifest.xml 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/optical_flag_calibration/manifest.xml 2009-06-18 10:06:30 UTC (rev 17279)
@@ -12,6 +12,7 @@
<!-- depend package="image_msgs" / -->
<!-- depend package="newmat10"/ -->
<depend package="pr2_mechanism_controllers" />
+ <depend package="manipulation_msgs" />
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
Modified: pkg/trunk/calibration/optical_flag_calibration/scripts/flag_tester.py
===================================================================
--- pkg/trunk/calibration/optical_flag_calibration/scripts/flag_tester.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/calibration/optical_flag_calibration/scripts/flag_tester.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -9,6 +9,7 @@
from pr2_mechanism_controllers.srv import *
from pr2_mechanism_controllers.msg import *
from robot_msgs.msg import *
+from manipulation_msgs.msg import *
cmd_count = 0
Added: pkg/trunk/common/manipulation_msgs/msg/JointTraj.msg
===================================================================
--- pkg/trunk/common/manipulation_msgs/msg/JointTraj.msg (rev 0)
+++ pkg/trunk/common/manipulation_msgs/msg/JointTraj.msg 2009-06-18 10:06:30 UTC (rev 17279)
@@ -0,0 +1 @@
+JointTrajPoint[] points
\ No newline at end of file
Added: pkg/trunk/common/manipulation_msgs/msg/JointTrajPoint.msg
===================================================================
--- pkg/trunk/common/manipulation_msgs/msg/JointTrajPoint.msg (rev 0)
+++ pkg/trunk/common/manipulation_msgs/msg/JointTrajPoint.msg 2009-06-18 10:06:30 UTC (rev 17279)
@@ -0,0 +1,2 @@
+float64[] positions
+float64 time
\ No newline at end of file
Deleted: pkg/trunk/common/robot_msgs/msg/JointTraj.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/JointTraj.msg 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/common/robot_msgs/msg/JointTraj.msg 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1 +0,0 @@
-JointTrajPoint[] points
\ No newline at end of file
Deleted: pkg/trunk/common/robot_msgs/msg/JointTrajPoint.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/JointTrajPoint.msg 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/common/robot_msgs/msg/JointTrajPoint.msg 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1,2 +0,0 @@
-float64[] positions
-float64 time
\ No newline at end of file
Deleted: pkg/trunk/common/robot_srvs/srv/IKService.srv
===================================================================
--- pkg/trunk/common/robot_srvs/srv/IKService.srv 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/common/robot_srvs/srv/IKService.srv 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1,6 +0,0 @@
-Header header
-robot_msgs/Pose pose
-robot_msgs/JointTrajPoint joint_pos
-duration timeout
----
-robot_msgs/JointTraj traj
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -56,8 +56,8 @@
#include <pr2_mechanism_controllers/SetJointTarget.h>
#include <pr2_mechanism_controllers/JointPosCmd.h>
-#include <robot_msgs/JointTraj.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTrajPoint.h>
#include <diagnostic_msgs/DiagnosticMessage.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
@@ -228,9 +228,9 @@
void deleteTrajectoryFromQueue(int id);
- void addTrajectoryToQueue(robot_msgs::JointTraj new_traj, int id);
+ void addTrajectoryToQueue(manipulation_msgs::JointTraj new_traj, int id);
- int createTrajectory(const robot_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory);
+ int createTrajectory(const manipulation_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory);
void updateTrajectoryQueue(int last_trajectory_finish_status);
@@ -247,7 +247,7 @@
*/
boost::mutex ros_lock_;
- robot_msgs::JointTraj traj_msg_;
+ manipulation_msgs::JointTraj traj_msg_;
pr2_mechanism_controllers::JointPosCmd msg_; //The message used by the ROS callback
ArmTrajectoryController *c_;
@@ -280,11 +280,11 @@
int trajectory_id_;
- std::vector<robot_msgs::JointTraj> joint_trajectory_vector_;
+ std::vector<manipulation_msgs::JointTraj> joint_trajectory_vector_;
std::vector<int> joint_trajectory_id_;
- void setTrajectoryCmdFromMsg(robot_msgs::JointTraj traj_msg);
+ void setTrajectoryCmdFromMsg(manipulation_msgs::JointTraj traj_msg);
int request_trajectory_id_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_trajectory_controller.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_trajectory_controller.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -37,8 +37,8 @@
#include <robot_msgs/PoseDot.h>
#include <pr2_robot_actions/Pose2D.h>
-#include <robot_msgs/JointTrajPoint.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTraj.h>
#include <trajectory/trajectory.h>
#include <tf/tf.h>
@@ -86,8 +86,8 @@
double controller_frequency_;
std::string control_topic_name_, path_input_topic_name_;
std::string trajectory_type_;
- robot_msgs::JointTraj path_msg_in_;
- robot_msgs::JointTraj path_msg_;
+ manipulation_msgs::JointTraj path_msg_in_;
+ manipulation_msgs::JointTraj path_msg_;
ros::Node& ros_node_;
tf::TransformListener& tf_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -41,8 +41,8 @@
#include <robot_mechanism_controllers/joint_pd_controller.h>
// Services
-#include <robot_msgs/JointTraj.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTrajPoint.h>
#include <diagnostic_msgs/DiagnosticMessage.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
@@ -189,7 +189,7 @@
*/
boost::mutex ros_lock_;
- robot_msgs::JointTraj traj_msg_; /**< The trajectory message received over ROS */
+ manipulation_msgs::JointTraj traj_msg_; /**< The trajectory message received over ROS */
/*!
* \brief node name
@@ -206,7 +206,7 @@
*/
ros::Node * const node_;
- std::vector<robot_msgs::JointTraj> joint_trajectory_vector_; /**< Vector of trajectory requests */
+ std::vector<manipulation_msgs::JointTraj> joint_trajectory_vector_; /**< Vector of trajectory requests */
std::vector<int> joint_trajectory_id_; /**< Vector of ids for trajectory requests */
@@ -366,7 +366,7 @@
* @param traj_msg Trajectory message received on a topic or a service
* @param id The associated id for the trajectory command
*/
- void setTrajectoryCmdFromMsg(robot_msgs::JointTraj traj_msg, int id);
+ void setTrajectoryCmdFromMsg(manipulation_msgs::JointTraj traj_msg, int id);
/**
* @brief Callback when a trajectory message is received on a topic
@@ -406,28 +406,28 @@
* @param new_traj The trajectory message that needs to be converted
* @param tp The resultant vector of TPoints
*/
- bool createTrajectoryPointsVectorFromMsg(const robot_msgs::JointTraj &new_traj, std::vector<trajectory::Trajectory::TPoint> &tp);
+ bool createTrajectoryPointsVectorFromMsg(const manipulation_msgs::JointTraj &new_traj, std::vector<trajectory::Trajectory::TPoint> &tp);
/**
* @brief Create a trajectory object from a trajectory message
* @param new_traj The trajectory message that needs to be converted
* @param return_trajectory The resultant trajectory object
*/
- bool createTrajectoryFromMsg(const robot_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory);
+ bool createTrajectoryFromMsg(const manipulation_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory);
/**
* @brief Add a new trajectory request to the queue of trajectories that need to be sent out
* @param new_traj The trajectory message that needs to be queued
* @param id The id of the trajectory to be queued
*/
- void addTrajectoryToQueue(robot_msgs::JointTraj new_traj, int id);
+ void addTrajectoryToQueue(manipulation_msgs::JointTraj new_traj, int id);
/**
* @brief Preempt the current trajectory queue
* @param new_traj The trajectory message that needs to executed
* @param id The id of the trajectory
*/
- void preemptTrajectoryQueue(robot_msgs::JointTraj new_traj, int id);
+ void preemptTrajectoryQueue(manipulation_msgs::JointTraj new_traj, int id);
/**
* @brief Delete a trajectory from the queue of trajectories
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -56,8 +56,8 @@
#include <pr2_mechanism_controllers/SetJointTarget.h>
#include <pr2_mechanism_controllers/JointPosCmd.h>
-#include <robot_msgs/JointTraj.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTrajPoint.h>
#include <diagnostic_msgs/DiagnosticMessage.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
@@ -271,9 +271,9 @@
void deleteTrajectoryFromQueue(int id);
- void addTrajectoryToQueue(robot_msgs::JointTraj new_traj, int id);
+ void addTrajectoryToQueue(manipulation_msgs::JointTraj new_traj, int id);
- int createTrajectory(const robot_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory);
+ int createTrajectory(const manipulation_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory);
void updateTrajectoryQueue(int last_trajectory_finish_status);
@@ -294,7 +294,7 @@
*/
boost::mutex ros_lock_;
- robot_msgs::JointTraj traj_msg_;
+ manipulation_msgs::JointTraj traj_msg_;
pr2_mechanism_controllers::JointPosCmd msg_; //The message used by the ROS callback
WholeBodyTrajectoryController *c_;
@@ -327,11 +327,11 @@
int trajectory_id_;
- std::vector<robot_msgs::JointTraj> joint_trajectory_vector_;
+ std::vector<manipulation_msgs::JointTraj> joint_trajectory_vector_;
std::vector<int> joint_trajectory_id_;
- void setTrajectoryCmdFromMsg(robot_msgs::JointTraj traj_msg);
+ void setTrajectoryCmdFromMsg(manipulation_msgs::JointTraj traj_msg);
int request_trajectory_id_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-06-18 10:06:30 UTC (rev 17279)
@@ -25,6 +25,8 @@
<depend package="angles" />
<depend package="control_toolbox" />
<depend package="filters" />
+ <depend package="manipulation_msgs" />
+
<url>http://pr.willowgarage.com</url>
<repository>http://pr.willowgarage.com/repos</repository>
<export>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/scripts/tuckarm.py
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/scripts/tuckarm.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/scripts/tuckarm.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -39,7 +39,7 @@
import rospy
-from robot_msgs.msg import JointTraj, JointTrajPoint
+from manipulation_msgs.msg import JointTraj, JointTrajPoint
from mechanism_control import mechanism
from robot_mechanism_controllers.srv import *
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -435,7 +435,7 @@
}
}
-void ArmTrajectoryControllerNode::setTrajectoryCmdFromMsg(robot_msgs::JointTraj traj_msg)
+void ArmTrajectoryControllerNode::setTrajectoryCmdFromMsg(manipulation_msgs::JointTraj traj_msg)
{
std::vector<trajectory::Trajectory::TPoint> tp;
int msg_size = std::max<int>((int)traj_msg.get_points_size(),1);
@@ -614,7 +614,7 @@
return true;
}
-int ArmTrajectoryControllerNode::createTrajectory(const robot_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory)
+int ArmTrajectoryControllerNode::createTrajectory(const manipulation_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory)
{
std::vector<trajectory::Trajectory::TPoint> tp;
@@ -654,7 +654,7 @@
return 1;
}
-void ArmTrajectoryControllerNode::addTrajectoryToQueue(robot_msgs::JointTraj new_traj, int id)
+void ArmTrajectoryControllerNode::addTrajectoryToQueue(manipulation_msgs::JointTraj new_traj, int id)
{
joint_trajectory_vector_.push_back(new_traj);
joint_trajectory_id_.push_back(id);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -741,7 +741,7 @@
}
-void JointTrajectoryController::setTrajectoryCmdFromMsg(robot_msgs::JointTraj traj_msg, int id)
+void JointTrajectoryController::setTrajectoryCmdFromMsg(manipulation_msgs::JointTraj traj_msg, int id)
{
std::vector<trajectory::Trajectory::TPoint> tp;
int msg_size = std::max<int>((int)traj_msg.get_points_size(),1);
@@ -894,7 +894,7 @@
}
-bool JointTrajectoryController::createTrajectoryPointsVectorFromMsg(const robot_msgs::JointTraj &new_traj, std::vector<trajectory::Trajectory::TPoint> &tp)
+bool JointTrajectoryController::createTrajectoryPointsVectorFromMsg(const manipulation_msgs::JointTraj &new_traj, std::vector<trajectory::Trajectory::TPoint> &tp)
{
if(new_traj.get_points_size() > 0)
{
@@ -925,7 +925,7 @@
return true;
}
-bool JointTrajectoryController::createTrajectoryFromMsg(const robot_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory)
+bool JointTrajectoryController::createTrajectoryFromMsg(const manipulation_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory)
{
std::vector<trajectory::Trajectory::TPoint> tp;
@@ -945,7 +945,7 @@
return true;
}
-void JointTrajectoryController::addTrajectoryToQueue(robot_msgs::JointTraj new_traj, int id)
+void JointTrajectoryController::addTrajectoryToQueue(manipulation_msgs::JointTraj new_traj, int id)
{
trajectory_queue_.lock();
@@ -958,7 +958,7 @@
trajectory_queue_.unlock();
}
-void JointTrajectoryController::preemptTrajectoryQueue(robot_msgs::JointTraj new_traj, int id)
+void JointTrajectoryController::preemptTrajectoryQueue(manipulation_msgs::JointTraj new_traj, int id)
{
int index = std::max(current_trajectory_index_,0);
trajectory_queue_.try_lock();
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -666,7 +666,7 @@
}
}
-void WholeBodyTrajectoryControllerNode::setTrajectoryCmdFromMsg(robot_msgs::JointTraj traj_msg)
+void WholeBodyTrajectoryControllerNode::setTrajectoryCmdFromMsg(manipulation_msgs::JointTraj traj_msg)
{
std::vector<trajectory::Trajectory::TPoint> tp;
int msg_size = std::max<int>((int)traj_msg.get_points_size(),1);
@@ -839,7 +839,7 @@
return true;
}
-int WholeBodyTrajectoryControllerNode::createTrajectory(const robot_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory)
+int WholeBodyTrajectoryControllerNode::createTrajectory(const manipulation_msgs::JointTraj &new_traj,trajectory::Trajectory &return_trajectory)
{
std::vector<trajectory::Trajectory::TPoint> tp;
@@ -879,7 +879,7 @@
return 1;
}
-void WholeBodyTrajectoryControllerNode::addTrajectoryToQueue(robot_msgs::JointTraj new_traj, int id)
+void WholeBodyTrajectoryControllerNode::addTrajectoryToQueue(manipulation_msgs::JointTraj new_traj, int id)
{
joint_trajectory_vector_.push_back(new_traj);
joint_trajectory_id_.push_back(id);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/srv/GraspPointSrv.srv
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/srv/GraspPointSrv.srv 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/srv/GraspPointSrv.srv 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1,3 +1,3 @@
robot_msgs/PoseStamped transform
---
-robot_msgs/JointTraj traj
\ No newline at end of file
+manipulation_msgs/JointTraj traj
\ No newline at end of file
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/srv/TrajectoryStart.srv
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/srv/TrajectoryStart.srv 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/srv/TrajectoryStart.srv 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1,5 +1,5 @@
## Starts a trajectory
-robot_msgs/JointTraj traj
+manipulation_msgs/JointTraj traj
uint8 hastiming # if 1, use timestamps of trajectory points, otherwise do internal retiming
uint8 requesttiming # if 1, send back the timestamps for every trajectory point (first point starts at 0)
---
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_trajectory_controller.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -33,7 +33,7 @@
*********************************************************************/
#include <ros/node.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
static int done = 0;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_joint_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_joint_trajectory_controller.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_joint_trajectory_controller.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -33,7 +33,7 @@
*********************************************************************/
#include <ros/node.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
static int done = 0;
@@ -55,7 +55,7 @@
/*********** Start moving the robot ************/
- robot_msgs::JointTraj cmd;
+ manipulation_msgs::JointTraj cmd;
int num_points = 1;
int num_joints = 3;
@@ -70,7 +70,7 @@
cmd.points[0].positions[2] = 0.0;
cmd.points[0].time = 0.0;
- node->advertise<robot_msgs::JointTraj>("base/trajectory_controller/command",1);
+ node->advertise<manipulation_msgs::JointTraj>("base/trajectory_controller/command",1);
sleep(1);
node->publish("base/trajectory_controller/command",cmd);
sleep(4);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_whole_body_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_whole_body_controller.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_whole_body_controller.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -33,7 +33,7 @@
*********************************************************************/
#include <ros/node.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
static int done = 0;
@@ -55,7 +55,7 @@
/*********** Start moving the robot ************/
- robot_msgs::JointTraj cmd;
+ manipulation_msgs::JointTraj cmd;
int num_points = 1;
int num_joints = 10;
@@ -77,7 +77,7 @@
cmd.points[0].positions[9] = -0.0;
cmd.points[0].time = 0.0;
- node->advertise<robot_msgs::JointTraj>("base/trajectory_controller/command",1);
+ node->advertise<manipulation_msgs::JointTraj>("base/trajectory_controller/command",1);
sleep(1);
node->publish("base/trajectory_controller/command",cmd);
sleep(4);
Modified: pkg/trunk/demos/plug_in/move_to_pickup.py
===================================================================
--- pkg/trunk/demos/plug_in/move_to_pickup.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/demos/plug_in/move_to_pickup.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -7,7 +7,8 @@
import numpy
import rospy
-from robot_msgs.msg import JointTraj, JointTrajPoint, PlugStow, Point, PoseStamped
+from robot_msgs.msg import PlugStow, Point, PoseStamped
+from mechanism_msgs.msg import JointTraj, JointTrajPoint
from mechanism_control import mechanism
from robot_mechanism_controllers.srv import *
from pr2_mechanism_controllers.srv import *
Modified: pkg/trunk/demos/tabletop_manipulation/scripts/tuckarm.py
===================================================================
--- pkg/trunk/demos/tabletop_manipulation/scripts/tuckarm.py 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/demos/tabletop_manipulation/scripts/tuckarm.py 2009-06-18 10:06:30 UTC (rev 17279)
@@ -36,7 +36,8 @@
import roslib
roslib.load_manifest('tabletop_manipulation')
import rospy
-from robot_msgs.msg import JointTraj, JointTrajPoint, MechanismState
+from manipulation_msgs.msg import JointTraj, JointTrajPoint
+from mechanism_msgs.msg import MechanismState
import sys
from math import *
Modified: pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -43,7 +43,7 @@
#include <robot_actions/action_runner.h>
#include <pr2_robot_actions/DoorActionState.h>
#include <pr2_robot_actions/Pose2D.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <ros/node.h>
Modified: pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -100,7 +100,7 @@
planner_ = new DoorReactivePlanner(ros_node_, tf_,&planner_cost_map_,control_frame_,global_frame_);
ROS_INFO("MAP SIZE: %d, %d", planner_cost_map_.cellSizeX(), planner_cost_map_.cellSizeY());
- ros_node_.advertise<robot_msgs::JointTraj>(control_topic_name_, 1);
+ ros_node_.advertise<manipulation_msgs::JointTraj>(control_topic_name_, 1);
last_diagnostics_publish_time_ = ros::Time::now();
ROS_INFO("Move base door action initialized");
@@ -353,7 +353,7 @@
void MoveBaseDoorAction::dispatchControl(const std::vector<pr2_robot_actions::Pose2D> &plan_in)
{
- robot_msgs::JointTraj plan_out;
+ manipulation_msgs::JointTraj plan_out;
current_distance_to_goal_ = distance(global_pose_.getOrigin().x(),global_pose_.getOrigin().y(),goal_.x,goal_.y);
if((int)plan_in.size() <= 0)
{
Modified: pkg/trunk/highlevel/move_arm/include/move_arm/move_arm.h
===================================================================
--- pkg/trunk/highlevel/move_arm/include/move_arm/move_arm.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/highlevel/move_arm/include/move_arm/move_arm.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -41,7 +41,7 @@
#include <robot_actions/action.h>
#include <robot_actions/action_runner.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <pr2_robot_actions/MoveArmState.h>
#include <pr2_robot_actions/MoveArmGoal.h>
#include <motion_planning_msgs/KinematicPath.h>
@@ -95,7 +95,7 @@
planning_environment::CollisionModels *collisionModels_;
planning_environment::PlanningMonitor *planningMonitor_;
- void fillTrajectoryPath(const motion_planning_msgs::KinematicPath &path, robot_msgs::JointTraj &traj);
+ void fillTrajectoryPath(const motion_planning_msgs::KinematicPath &path, manipulation_msgs::JointTraj &traj);
bool computeIK(const robot_msgs::PoseStamped &pose_stamped_msg, std::vector<double> &solution);
bool getControlJointNames(std::vector<std::string> &joint_names);
};
Modified: pkg/trunk/highlevel/move_arm/src/move_arm.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/move_arm.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/highlevel/move_arm/src/move_arm.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -362,7 +362,7 @@
return result;
}
- void MoveArm::fillTrajectoryPath(const motion_planning_msgs::KinematicPath &path, robot_msgs::JointTraj &traj)
+ void MoveArm::fillTrajectoryPath(const motion_planning_msgs::KinematicPath &path, manipulation_msgs::JointTraj &traj)
{
traj.points.resize(path.states.size());
for (unsigned int i = 0 ; i < path.states.size() ; ++i)
Modified: pkg/trunk/highlevel/plugs/plugs_core/include/plugs_core/action_untuck_arms.h
===================================================================
--- pkg/trunk/highlevel/plugs/plugs_core/include/plugs_core/action_untuck_arms.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/highlevel/plugs/plugs_core/include/plugs_core/action_untuck_arms.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -44,7 +44,7 @@
#include <std_msgs/Empty.h>
#include <robot_actions/action.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
#include <pr2_mechanism_controllers/TrajectoryCancel.h>
Modified: pkg/trunk/highlevel/safety/safety_core/include/safety_core/action_tuck_arms.h
===================================================================
--- pkg/trunk/highlevel/safety/safety_core/include/safety_core/action_tuck_arms.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/highlevel/safety/safety_core/include/safety_core/action_tuck_arms.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -44,7 +44,7 @@
#include <std_msgs/Empty.h>
#include <robot_actions/action.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
#include <pr2_mechanism_controllers/TrajectoryCancel.h>
Modified: pkg/trunk/motion_planning/mpglue/include/mpglue/plan.h
===================================================================
--- pkg/trunk/motion_planning/mpglue/include/mpglue/plan.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/mpglue/include/mpglue/plan.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -40,6 +40,8 @@
namespace robot_msgs {
class Pose;
+}
+namespace manipulation_msgs {
class JointTraj;
}
@@ -92,7 +94,7 @@
void addWaypoint(boost::shared_ptr<waypoint_s> wp);
static void convertToJointTraj(waypoint_plan_t const * plan,
- robot_msgs::JointTraj * jointTraj);
+ manipulation_msgs::JointTraj * jointTraj);
/**
Convert a plan from a raw state ID sequence (as computed by
Modified: pkg/trunk/motion_planning/mpglue/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/mpglue/manifest.xml 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/mpglue/manifest.xml 2009-06-18 10:06:30 UTC (rev 17279)
@@ -7,6 +7,7 @@
<url>http://pr.willowgarage.com/pr-docs/ros-packages/mpglue/html/</url>
<depend package="std_msgs"/>
<depend package="robot_msgs"/>
+ <depend package="manipulation_msgs"/>
<depend package="door_msgs"/>
<depend package="roscpp"/>
<depend package="costmap_2d"/>
Modified: pkg/trunk/motion_planning/mpglue/src/plan.cpp
===================================================================
--- pkg/trunk/motion_planning/mpglue/src/plan.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/mpglue/src/plan.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -36,7 +36,7 @@
#include <mpglue/plan.h>
#include <mpglue/sbpl_environment.h>
#include <robot_msgs/Pose.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <sfl/util/numeric.hpp>
namespace mpglue {
@@ -133,10 +133,10 @@
void PlanConverter::
convertToJointTraj(waypoint_plan_t const * plan,
- robot_msgs::JointTraj * jointTraj)
+ manipulation_msgs::JointTraj * jointTraj)
{
for (waypoint_plan_t::const_iterator ip(plan->begin()); ip != plan->end(); ++ip) {
- robot_msgs::JointTrajPoint pt;
+ manipulation_msgs::JointTrajPoint pt;
pt.positions.push_back((*ip)->x);
pt.positions.push_back((*ip)->y);
if ( ! (*ip)->ignoreTheta())
Modified: pkg/trunk/motion_planning/plan_ompl_path/src/plan_kinematic_path.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_ompl_path/src/plan_kinematic_path.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/plan_ompl_path/src/plan_kinematic_path.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -52,7 +52,7 @@
#include <motion_planning_msgs/DisplayKinematicPath.h>
// messages to interact with the joint trajectory controller
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
// message to interact with the cartesian trajectory controller
#include <robot_msgs/PoseStamped.h>
@@ -73,7 +73,7 @@
kmsm_ = new planning_environment::KinematicModelStateMonitor(rm_);
// we use the topic for sending commands to the controller, so we need to advertise it
- jointCommandPublisher_ = nh_.advertise<robot_msgs::JointTraj>("right_arm/trajectory_controller/trajectory_command", 1);
+ jointCommandPublisher_ = nh_.advertise<manipulation_msgs::JointTraj>("right_arm/trajectory_controller/trajectory_command", 1);
cartesianCommandPublisher_ = nh_.advertise<robot_msgs::PoseStamped>("right_arm/?/command", 1);
// advertise the topic for displaying kinematic plans
@@ -256,7 +256,7 @@
}
// convert a kinematic path message to a trajectory for the controller
- void getTrajectoryMsg(const motion_planning_msgs::KinematicPath &path, robot_msgs::JointTraj &traj)
+ void getTrajectoryMsg(const motion_planning_msgs::KinematicPath &path, manipulation_msgs::JointTraj &traj)
{
traj.set_points_size(path.get_states_size());
for (unsigned int i = 0 ; i < path.get_states_size() ; ++i)
@@ -272,7 +272,7 @@
void sendArmCommand(const motion_planning_msgs::KinematicPath &path, const std::string &model)
{
sendDisplay(path, model);
- robot_msgs::JointTraj traj;
+ manipulation_msgs::JointTraj traj;
getTrajectoryMsg(path, traj);
jointCommandPublisher_.publish(traj);
ROS_INFO("Sent trajectory to controller");
Modified: pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_replan_to_state.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_replan_to_state.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/execute_replan_to_state.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -45,7 +45,7 @@
#include <motion_planning_srvs/KinematicPlan.h>
// messages to interact with the trajectory controller
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <std_srvs/Empty.h>
@@ -63,7 +63,7 @@
kmsm_ = new planning_environment::KinematicModelStateMonitor(rm_);
// we use the topic for sending commands to the controller, so we need to advertise it
- jointCommandPublisher_ = nh_.advertise<robot_msgs::JointTraj>("right_arm/trajectory_controller/trajectory_command", 1);
+ jointCommandPublisher_ = nh_.advertise<manipulation_msgs::JointTraj>("right_arm/trajectory_controller/trajectory_command", 1);
}
~Example(void)
@@ -133,7 +133,7 @@
protected:
// convert a kinematic path message to a trajectory for the controller
- void getTrajectoryMsg(const motion_planning_msgs::KinematicPath &path, robot_msgs::JointTraj &traj)
+ void getTrajectoryMsg(const motion_planning_msgs::KinematicPath &path, manipulation_msgs::JointTraj &traj)
{
traj.set_points_size(path.get_states_size());
for (unsigned int i = 0 ; i < path.get_states_size() ; ++i)
@@ -148,7 +148,7 @@
// send a command to the trajectory controller using a topic
void sendArmCommand(const motion_planning_msgs::KinematicPath &path, const std::string &model)
{
- robot_msgs::JointTraj traj;
+ manipulation_msgs::JointTraj traj;
getTrajectoryMsg(path, traj);
jointCommandPublisher_.publish(traj);
ROS_INFO("Sent trajectory to controller (using a topic)");
Modified: pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/test_path_execution.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/test_path_execution.cpp 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/plan_ompl_path/src/right_arm/test_path_execution.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -40,7 +40,7 @@
is looked at as well. */
#include <planning_environment/kinematic_model_state_monitor.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
#include <cassert>
@@ -53,7 +53,7 @@
{
rm_ = new planning_environment::RobotModels("robot_description");
kmsm_ = new planning_environment::KinematicModelStateMonitor(rm_);
- jointCommandPublisher_ = nh_.advertise<robot_msgs::JointTraj>("right_arm/trajectory_controller/trajectory_command", 1);
+ jointCommandPublisher_ = nh_.advertise<manipulation_msgs::JointTraj>("right_arm/trajectory_controller/trajectory_command", 1);
sleep_duration_ = 4;
use_topic_ = false;
}
@@ -67,7 +67,7 @@
void testJointLimitsRightArm(const std::string& jname = "")
{
// we send a trajectory with one state
- robot_msgs::JointTraj traj;
+ manipulation_msgs::JointTraj traj;
const int controllerDim = 7;
std::string groupName = "right_arm";
traj.set_points_size(1);
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/include/sbpl_arm_executive/pr2_arm_node.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/include/sbpl_arm_executive/pr2_arm_node.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_executive/include/sbpl_arm_executive/pr2_arm_node.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -34,9 +34,9 @@
#include <std_msgs/Float64.h>
#include <robot_msgs/Pose.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <robot_msgs/PoseStamped.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTrajPoint.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
@@ -99,17 +99,17 @@
void goHome(const std::vector<double> &home_position);
- bool sendTrajectory(std::string group_name, const robot_msgs::JointTraj &traj);
+ bool sendTrajectory(std::string group_name, const manipulation_msgs::JointTraj &traj);
- void sendTrajectoryOnTopic(std::string group_name, const robot_msgs::JointTraj &traj);
+ void sendTrajectoryOnTopic(std::string group_name, const manipulation_msgs::JointTraj &traj);
- bool planSBPLPath(const robot_msgs::JointTrajPoint &joint_start, const std::vector<robot_msgs::Pose> &pose_goals, robot_msgs::JointTraj &planned_path);
+ bool planSBPLPath(const manipulation_msgs::JointTrajPoint &joint_start, const std::vector<robot_msgs::Pose> &pose_goals, manipulation_msgs::JointTraj &planned_path);
- bool planSBPLPath(const robot_msgs::JointTrajPoint &joint_start, const std::vector<robot_msgs::JointTrajPoint> &joint_goal, robot_msgs::JointTraj &planned_path);
+ bool planSBPLPath(const manipulation_msgs::JointTrajPoint &joint_start, const std::vector<manipulation_msgs::JointTrajPoint> &joint_goal, manipulation_msgs::JointTraj &planned_path);
- bool planSBPLPath_ioan(const robot_msgs::JointTrajPoint &joint_start, const std::vector<robot_msgs::Pose> &pose_goals, robot_msgs::JointTraj &planned_path);
+ bool planSBPLPath_ioan(const manipulation_msgs::JointTrajPoint &joint_start, const std::vector<robot_msgs::Pose> &pose_goals, manipulation_msgs::JointTraj &planned_path);
- void getCurrentPosition(robot_msgs::JointTrajPoint ¤t_joint_positions);
+ void getCurrentPosition(manipulation_msgs::JointTrajPoint ¤t_joint_positions);
robot_msgs::Pose RPYToTransform(double roll, double pitch, double yaw, double x, double y, double z);
@@ -119,7 +119,7 @@
void shakeHead();
- void getGraspTrajectory(const robot_msgs::PoseStamped &transform, robot_msgs::JointTraj &traj);
+ void getGraspTrajectory(const robot_msgs::PoseStamped &transform, manipulation_msgs::JointTraj &traj);
};
}
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_check_path.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -38,10 +38,10 @@
#include <tf/tf.h>
/** Messages needed for trajectory control and collision map**/
-#include <robot_msgs/Pose.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/Pose.h>
+#include <manipulation_msgs/JointTraj.h>
#include <robot_msgs/CollisionMap.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTrajPoint.h>
/** sbpl planner include files **/
#include <sbpl_arm_planner/headers.h>
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -39,9 +39,9 @@
/** Messages needed for trajectory control and collision map**/
#include <robot_msgs/Pose.h>
-#include <robot_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTraj.h>
#include <robot_msgs/CollisionMap.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTrajPoint.h>
/** sbpl planner include files **/
#include <sbpl_arm_planner/headers.h>
@@ -104,13 +104,13 @@
bool initializePlannerAndEnvironment();
- bool setStart(const robot_msgs::JointTrajPoint &start);
+ bool setStart(const manipulation_msgs::JointTrajPoint &start);
bool setGoals(const std::vector<robot_msgs::Pose> &goals);
- bool setGoals(const robot_msgs::JointTrajPoint &goal_joint_positions_);
+ bool setGoals(const manipulation_msgs::JointTrajPoint &goal_joint_positions_);
- bool replan(robot_msgs::JointTraj &arm_path);
+ bool replan(manipulation_msgs::JointTraj &arm_path);
void getSBPLCollisionMap();
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/manifest.xml 2009-06-18 10:06:30 UTC (rev 17279)
@@ -7,6 +7,7 @@
<depend package="roscpp"/>
<depend package="std_msgs"/>
<depend package="robot_msgs" />
+ <depend package="manipulation_msgs" />
<depend package="motion_planning_msgs" />
<depend package="motion_planning_srvs" />
<depend package="sbpl_arm_planner" />
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/CheckPathSrv.srv
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/CheckPathSrv.srv 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/CheckPathSrv.srv 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1,2 +1,2 @@
-robot_msgs/JointTraj traj
+manipulation_msgs/JointTraj traj
---
Modified: pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/PlanPathSrv.srv
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/PlanPathSrv.srv 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/srv/PlanPathSrv.srv 2009-06-18 10:06:30 UTC (rev 17279)
@@ -1,6 +1,6 @@
std_msgs/String type
-robot_msgs/JointTrajPoint start
-robot_msgs/JointTrajPoint joint_goal
+manipulation_msgs/JointTrajPoint start
+manipulation_msgs/JointTrajPoint joint_goal
robot_msgs/Pose[] cartesian_goals
---
-robot_msgs/JointTraj traj
+manipulation_msgs/JointTraj traj
Modified: pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/include/sbpl_door_planner_action/sbpl_door_planner_action.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -44,8 +44,8 @@
/** Messages needed for trajectory control and collision map**/
#include <robot_msgs/Pose.h>
-#include <robot_msgs/JointTraj.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTrajPoint.h>
#include <robot_msgs/CollisionMap.h>
// Costmap used for the map representation
@@ -129,7 +129,7 @@
bool initializePlannerAndEnvironment(const door_msgs::Door &door);
- bool makePlan(const pr2_robot_actions::Pose2D &start, const pr2_robot_actions::Pose2D &goal, robot_msgs::JointTraj &path);
+ bool makePlan(const pr2_robot_actions::Pose2D &start, const pr2_robot_actions::Pose2D &goal, manipulation_msgs::JointTraj &path);
std::vector<robot_msgs::Point> footprint_;
@@ -151,7 +151,7 @@
bool removeDoor();
- void publishPath(const robot_msgs::JointTraj &path, std::string topic, double r, double g, double b, double a);
+ void publishPath(const manipulation_msgs::JointTraj &path, std::string topic, double r, double g, double b, double a);
bool computeOrientedFootprint(const pr2_robot_actions::Pose2D &position, const std::vector<robot_msgs::Point>& footprint_spec, std::vector<robot_msgs::Point>& oriented_footprint);
@@ -171,7 +171,7 @@
double handle_hinge_distance_;
- void animate(const robot_msgs::JointTraj &path);
+ void animate(const manipulation_msgs::JointTraj &path);
tf::Stamped<tf::Pose> getGlobalHandlePosition(const door_msgs::Door &door, const double &local_angle);
@@ -183,7 +183,7 @@
std::string arm_control_topic_name_;
- void dispatchControl(const robot_msgs::JointTraj &path, const door_msgs::Door &door);
+ void dispatchControl(const manipulation_msgs::JointTraj &path, const door_msgs::Door &door);
double distance_goal_;
@@ -193,7 +193,7 @@
void publishGripper(const double &angle);
- void processPlan(const robot_msgs::JointTraj &path, robot_msgs::JointTraj &return_path);
+ void processPlan(const manipulation_msgs::JointTraj &path, manipulation_msgs::JointTraj &return_path);
bool do_control_;
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-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_door_planner_action/src/sbpl_door_planner_action.cpp 2009-06-18 10:06:30 UTC (rev 17279)
@@ -103,7 +103,7 @@
// ros_node_.advertise<robot_msgs::PoseStamped>(arm_control_topic_name_,1);
ros_node_.advertise<pr2_ik::PoseCmd>(arm_control_topic_name_,1);
- ros_node_.advertise<robot_msgs::JointTraj>(base_control_topic_name_,1);
+ ros_node_.advertise<manipulation_msgs::JointTraj>(base_control_topic_name_,1);
robot_msgs::Point pt;
//create a square footprint
@@ -238,7 +238,7 @@
return true;
}
-bool SBPLDoorPlanner::makePlan(const pr2_robot_actions::Pose2D &start, const pr2_robot_actions::Pose2D &goal, robot_msgs::JointTraj &path)
+bool SBPLDoorPlanner::makePlan(const pr2_robot_actions::Pose2D &start, const pr2_robot_actions::Pose2D &goal, manipulation_msgs::JointTraj &path)
{
ROS_INFO("[replan] getting fresh copy of costmap");
lock_.lock();
@@ -318,7 +318,7 @@
ROS_DEBUG("Found a path with %d points",(int) plan->size());
for(int i=0; i < (int) plan->size(); i++)
{
- robot_msgs::JointTrajPoint path_point;
+ manipulation_msgs::JointTrajPoint path_point;
mpglue::waypoint_s const * wpt((*plan)[i].get());
mpglue::door_waypoint_s const * doorwpt(dynamic_cast<mpglue::door_waypoint_s const *>(wpt));
path_point.positions.push_back(doorwpt->x);
@@ -344,7 +344,7 @@
// path.points.clear();
// for(int i=0; i < (int) return_path.size(); i++)
// {
-// robot_msgs::JointTrajPoint path_point;
+// manipulation_msgs::JointTrajPoint path_point;
// path_point.positions.push_back(return_path[i].x);
// path_point.positions.push_back(return_path[i].y);
// path_point.positions.push_back(return_path[i].th);
@@ -358,7 +358,7 @@
robot_actions::ResultStatus SBPLDoorPlanner::execute(const door_msgs::Door& door_msg_in, door_msgs::Door& feedback)
{
- robot_msgs::JointTraj path;
+ manipulation_msgs::JointTraj path;
door_msgs::Door door;
if(!updateGlobalPose())
{
@@ -412,7 +412,7 @@
handle_hinge_distance_ = getHandleHingeDistance(door_env_.door);
- robot_msgs::JointTraj new_path;
+ manipulation_msgs::JointTraj new_path;
processPlan(path,new_path);
if(animate_ && !isPreemptRequested())
@@ -432,14 +432,14 @@
return robot_actions::SUCCESS;
}
-void SBPLDoorPlanner::dispatchControl(const robot_msgs::JointTraj &path, const door_msgs::Door &door)
+void SBPLDoorPlanner::dispatchControl(const manipulation_msgs::JointTraj &path, const door_msgs::Door &door)
{
int plan_count = 0;
ros::Rate control_rate(controller_frequency_);
while(!isPreemptRequested() && plan_count < (int) path.get_points_size())
{
- robot_msgs::JointTraj base_plan;
- robot_msgs::JointTrajPoint path_point;
+ manipulation_msgs::JointTraj base_plan;
+ manipulation_msgs::JointTrajPoint path_point;
path_point.positions.push_back(path.points[plan_count].positions[0]);
path_point.positions.push_back(path.points[plan_count].positions[1]);
path_point.positions.push_back(angles::normalize_angle(path.points[plan_count].positions[2]));
@@ -470,7 +470,7 @@
}
}
-void SBPLDoorPlanner::processPlan(const robot_msgs::JointTraj &path, robot_msgs::JointTraj &return_path)
+void SBPLDoorPlanner::processPlan(const manipulation_msgs::JointTraj &path, manipulation_msgs::JointTraj &return_path)
{
return_path = path;
double global_yaw = getFrameAngle(door_env_.door); //Take the plan and add the last few steps to open the door
@@ -483,7 +483,7 @@
double delta_open_angle = 0.05;
int num_intervals = fabs(additional_open_angle)/delta_open_angle;
- robot_msgs::JointTrajPoint additional_point = path.points.back();
+ manipulation_msgs::JointTrajPoint additional_point = path.points.back();
for(int i=0; i<num_intervals; i++)
{
additional_point.positions[3] = angles::normalize_angle(last_plan_angle + i*additional_open_angle/(double)num_intervals);
@@ -499,7 +499,7 @@
}
-void SBPLDoorPlanner::animate(const robot_msgs::JointTraj &path)
+void SBPLDoorPlanner::animate(const manipulation_msgs::JointTraj &path)
{
ros::Rate animate_rate(animate_frequency_);
for(int i=0; i < (int) path.get_points_size(); i++)
@@ -591,7 +591,7 @@
return result;
}
-void SBPLDoorPlanner::publishPath(const robot_msgs::JointTraj &path, std::string topic, double r, double g, double b, double a)
+void SBPLDoorPlanner::publishPath(const manipulation_msgs::JointTraj &path, std::string topic, double r, double g, double b, double a)
{
visualization_msgs::Polyline gui_path_msg;
gui_path_msg.header.frame_id = global_frame_;
Modified: pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h
===================================================================
--- pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h 2009-06-18 09:27:04 UTC (rev 17278)
+++ pkg/trunk/motion_planning/planning_research/sbpl_planner_node/include/sbpl_planner_node/sbpl_planner_node.h 2009-06-18 10:06:30 UTC (rev 17279)
@@ -43,8 +43,8 @@
/** Messages needed for trajectory control and collision map**/
#include <robot_msgs/Pose.h>
-#include <robot_msgs/JointTraj.h>
-#include <robot_msgs/JointTrajPoint.h>
+#include <manipulation_msgs/JointTraj.h>
+#include <manipulation_msgs/JointTrajPoint.h>
#include <robot_msgs/CollisionMap.h>
// Co...
[truncated message content] |