|
From: <mee...@us...> - 2009-08-08 00:15:26
|
Revision: 21089
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21089&view=rev
Author: meeussen
Date: 2009-08-08 00:13:36 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
move wrench message from robot_msgs to geometry_msgs and remove header from message
Modified Paths:
--------------
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_chain_constraint_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/msg/CartesianHybridState.msg
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/plug_controller.h
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_msgs/msg/Wrench.msg
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-08-08 00:13:36 UTC (rev 21089)
@@ -39,7 +39,7 @@
#include <kdl/frames.hpp>
#include <kdl/chainjnttojacsolver.hpp>
#include <ros/node_handle.h>
-#include <robot_msgs/Wrench.h>
+#include <geometry_msgs/Wrench.h>
#include <mechanism_control/controller.h>
#include <mechanism_model/chain.h>
#include <tf/transform_datatypes.h>
@@ -70,7 +70,7 @@
ros::NodeHandle node_;
ros::Subscriber sub_command_;
- void command(const robot_msgs::WrenchConstPtr& wrench_msg);
+ void command(const geometry_msgs::WrenchConstPtr& wrench_msg);
mechanism::RobotState *robot_state_;
mechanism::Chain chain_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h 2009-08-08 00:13:36 UTC (rev 21089)
@@ -42,7 +42,7 @@
#include "kdl/chainfksolver.hpp"
#include "kdl/chainjnttojacsolver.hpp"
#include "ros/node.h"
-#include "robot_msgs/Wrench.h"
+#include "geometry_msgs/Wrench.h"
#include "misc_utils/subscription_guard.h"
#include "mechanism_control/controller.h"
#include "tf/transform_datatypes.h"
@@ -132,7 +132,7 @@
EndeffectorConstraintController controller_;
SubscriptionGuard guard_command_;
- robot_msgs::Wrench wrench_msg_;
+ geometry_msgs::Wrench wrench_msg_;
unsigned int loop_count_;
};
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_chain_constraint_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_chain_constraint_controller.h 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_chain_constraint_controller.h 2009-08-08 00:13:36 UTC (rev 21089)
@@ -59,7 +59,7 @@
#include <kdl/chainjnttojacsolver.hpp>
#include "ros/node.h"
#include "control_toolbox/pid.h"
-#include "robot_msgs/Wrench.h"
+#include "geometry_msgs/Wrench.h"
#include "robot_mechanism_controllers/ChangeConstraints.h"
#include "robot_mechanism_controllers/JointConstraint.h"
#include "mechanism_control/controller.h"
@@ -173,7 +173,7 @@
JointChainConstraintController controller_;
mechanism::RobotState *robot_;
- robot_msgs::Wrench wrench_msg_;
+ geometry_msgs::Wrench wrench_msg_;
};
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/plug_controller.h 2009-08-08 00:13:36 UTC (rev 21089)
@@ -41,7 +41,7 @@
#include "kdl/frames.hpp"
#include "kdl/chainfksolver.hpp"
#include "ros/node.h"
-#include "robot_msgs/Wrench.h"
+#include "geometry_msgs/Wrench.h"
#include "robot_msgs/PoseStamped.h"
#include "robot_msgs/Transform.h"
#include "robot_mechanism_controllers/PlugInternalState.h"
@@ -166,7 +166,7 @@
SubscriptionGuard guard_outlet_pose_;
AdvertisedServiceGuard guard_set_tool_frame_;
- robot_msgs::Wrench wrench_msg_;
+ geometry_msgs::Wrench wrench_msg_;
robot_msgs::PoseStamped outlet_pose_msg_;
unsigned int loop_count_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/msg/CartesianHybridState.msg
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/msg/CartesianHybridState.msg 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/msg/CartesianHybridState.msg 2009-08-08 00:13:36 UTC (rev 21089)
@@ -8,7 +8,7 @@
geometry_msgs/Twist last_twist_meas
geometry_msgs/Twist last_twist_meas_filtered
geometry_msgs/Twist last_twist_desi
-robot_msgs/Wrench last_wrench_desi
+geometry_msgs/Wrench last_wrench_desi
float64[] desired_torque
float64[] measured_torque
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_hybrid_controller.cpp 2009-08-08 00:13:36 UTC (rev 21089)
@@ -66,7 +66,7 @@
m.angular.z = k.rot.z();
}
-void WrenchKDLToMsg(const KDL::Wrench &k, robot_msgs::Wrench &m)
+void WrenchKDLToMsg(const KDL::Wrench &k, geometry_msgs::Wrench &m)
{
m.force.x = k.force.x();
m.force.y = k.force.y();
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-08-08 00:13:36 UTC (rev 21089)
@@ -130,7 +130,7 @@
// subscribe to wrench commands
- sub_command_ = node_.subscribe<robot_msgs::Wrench>
+ sub_command_ = node_.subscribe<geometry_msgs::Wrench>
("command", 1, &CartesianWrenchController::command, this);
return true;
@@ -203,7 +203,7 @@
-void CartesianWrenchController::command(const robot_msgs::WrenchConstPtr& wrench_msg)
+void CartesianWrenchController::command(const geometry_msgs::WrenchConstPtr& wrench_msg)
{
// convert to wrench command
wrench_desi_.force(0) = wrench_msg->force.x;
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-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/motion_planning/planning_research/sbpl_arm_planner_node/include/sbpl_arm_planner_node/sbpl_arm_planner_node.h 2009-08-08 00:13:36 UTC (rev 21089)
@@ -50,7 +50,7 @@
#include <kdl/chainjnttojacsolver.hpp>
/** Messages **/
-#include <robot_msgs/Wrench.h>
+#include <geometry_msgs/Wrench.h>
#include <geometry_msgs/Pose.h>
#include <manipulation_msgs/JointTraj.h>
#include <mapping_msgs/CollisionMap.h>
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/plug_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/plug_controller.h 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/plug_controller.h 2009-08-08 00:13:36 UTC (rev 21089)
@@ -42,7 +42,7 @@
#include "kdl/chainfksolver.hpp"
#include "kdl/chainjnttojacsolver.hpp"
#include "ros/node.h"
-#include "robot_msgs/Wrench.h"
+#include "geometry_msgs/Wrench.h"
#include "geometry_msgs/PoseStamped.h"
#include "geometry_msgs/Transform.h"
#include "experimental_controllers/PlugInternalState.h"
@@ -167,7 +167,7 @@
SubscriptionGuard guard_outlet_pose_;
AdvertisedServiceGuard guard_set_tool_frame_;
- robot_msgs::Wrench wrench_msg_;
+ geometry_msgs::Wrench wrench_msg_;
geometry_msgs::PoseStamped outlet_pose_msg_;
unsigned int loop_count_;
Deleted: pkg/trunk/stacks/common_msgs/robot_msgs/msg/Wrench.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_msgs/msg/Wrench.msg 2009-08-07 23:39:29 UTC (rev 21088)
+++ pkg/trunk/stacks/common_msgs/robot_msgs/msg/Wrench.msg 2009-08-08 00:13:36 UTC (rev 21089)
@@ -1,3 +0,0 @@
-Header header
-geometry_msgs/Vector3 force
-geometry_msgs/Vector3 torque
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|