|
From: <rob...@us...> - 2008-10-14 01:22:10
|
Revision: 5314
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=5314&view=rev
Author: rob_wheeler
Date: 2008-10-14 00:48:39 +0000 (Tue, 14 Oct 2008)
Log Message:
-----------
Move mechanism_control msgs and srvs to robot_msgs and robot_srvs.
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp
pkg/trunk/highlevel/highlevel_controllers/src/ControlCli.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp
pkg/trunk/highlevel/highlevel_controllers/src/MoveEndEffector.cpp
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/mechanism/mechanism_control/scripts/detect.py
pkg/trunk/mechanism/mechanism_control/scripts/listen.py
pkg/trunk/mechanism/mechanism_control/scripts/writer.py
pkg/trunk/mechanism/mechanism_control/src/mechanism_control/mechanism.py
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/mechanism/mechanism_control/test/ms_publisher_test.cpp
pkg/trunk/mechanism/mechanism_control_rt/manifest.xml
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/pr2_msgs/manifest.xml
pkg/trunk/pr2_msgs/msg/MoveArmGoal.msg
pkg/trunk/pr2_msgs/msg/MoveArmState.msg
pkg/trunk/pr2_msgs/msg/MoveEndEffectorGoal.msg
pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg
Added Paths:
-----------
pkg/trunk/robot_msgs/msg/ActuatorState.msg
pkg/trunk/robot_msgs/msg/JointState.msg
pkg/trunk/robot_msgs/msg/MechanismState.msg
pkg/trunk/robot_srvs/srv/KillController.srv
pkg/trunk/robot_srvs/srv/ListControllerTypes.srv
pkg/trunk/robot_srvs/srv/ListControllers.srv
pkg/trunk/robot_srvs/srv/SpawnController.srv
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_arm_dynamics_controller.cpp 2008-10-14 00:48:39 UTC (rev 5314)
@@ -54,7 +54,7 @@
~test_run_arm(){};
- mechanism_control::MechanismState state;
+ robot_msgs::MechanismState state;
void jointMsgReceived()
{
Modified: pkg/trunk/highlevel/highlevel_controllers/src/ControlCli.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/ControlCli.cpp 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/highlevel/highlevel_controllers/src/ControlCli.cpp 2008-10-14 00:48:39 UTC (rev 5314)
@@ -37,7 +37,7 @@
#include <ros/node.h>
#include <pr2_msgs/MoveArmGoal.h>
-#include <mechanism_control/MechanismState.h>
+#include <robot_msgs/MechanismState.h>
#include <highlevel_controllers/PlugInGoal.h>
#include <highlevel_controllers/PlugInState.h>
#include <robot_srvs/PlanNames.h>
@@ -55,7 +55,7 @@
advertise<pr2_msgs::MoveArmGoal>("right_arm_goal", 1);
advertise<highlevel_controllers::PlugInGoal>("plugin_goal", 1);
advertise<robot_msgs::BatteryState>("battery_state", 1);
- advertise<mechanism_control::MechanismState>("mechanism_state", 1);
+ advertise<robot_msgs::MechanismState>("mechanism_state", 1);
runCLI();
}
bool alive() { return !dead; }
@@ -134,7 +134,7 @@
} else if (c == 'I') {
- mechanism_control::MechanismState mechanismState;
+ robot_msgs::MechanismState mechanismState;
std::vector<std::string> names;
fillNamesLeftArm(names);
@@ -146,7 +146,7 @@
mechanismState.joint_states[i].name = names[i];
}
printf("Publishing states.\n");
- publish<mechanism_control::MechanismState>("mechanism_state", mechanismState);
+ publish<robot_msgs::MechanismState>("mechanism_state", mechanismState);
} else if (c == 'S') {
std::vector<std::string> names;
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveArm.cpp 2008-10-14 00:48:39 UTC (rev 5314)
@@ -57,7 +57,7 @@
* @section topic ROS topics
*
* Subscribes to (name/type):
- * - @b "mechanism_state"/mechanism_control::MechanismState : The state of the robot joints and actuators
+ * - @b "mechanism_state"/robot_msgs::MechanismState : The state of the robot joints and actuators
* - @b "right_arm_goal"/pr2_msgs::MoveArmGoal : The new goal containing a setpoint to achieve for the joint angles
* - @b "left_arm_goal"/pr2_msgs::MoveArmGoal : The new goal containing a setpoint to achieve for the joint angles
*
@@ -74,7 +74,7 @@
#include <HighlevelController.hh>
#include <pr2_mechanism_controllers/JointPosCmd.h>
-#include <mechanism_control/MechanismState.h>
+#include <robot_msgs/MechanismState.h>
#include <pr2_msgs/MoveArmState.h>
#include <pr2_msgs/MoveArmGoal.h>
#include <robot_msgs/DisplayKinematicPath.h>
@@ -103,7 +103,7 @@
* @brief Helper Method to obtain the joint value by name
* @return true if the joint is present, otherwise false
*/
- bool readJointValue(const mechanism_control::MechanismState& mechanismStateMsg, const std::string& name, double& value);
+ bool readJointValue(const robot_msgs::MechanismState& mechanismStateMsg, const std::string& name, double& value);
void handleArmConfigurationCallback();
void updateGoalMsg();
@@ -117,7 +117,7 @@
const std::string armCmdTopic;
const std::string kinematicModel;
- mechanism_control::MechanismState mechanismState;
+ robot_msgs::MechanismState mechanismState;
robot_srvs::NamedKinematicPlanState::response plan;
unsigned int currentWaypoint; /*!< The waypoint in the plan that we are targetting */
rosTFClient tf_; /**< Used to do transforms */
@@ -127,7 +127,7 @@
};
-bool MoveArm::readJointValue(const mechanism_control::MechanismState& mechanismStateMsg, const std::string& name, double& value){
+bool MoveArm::readJointValue(const robot_msgs::MechanismState& mechanismStateMsg, const std::string& name, double& value){
for(unsigned int i = 0; i < mechanismStateMsg.get_joint_states_size(); i++){
const std::string& jointName = mechanismStateMsg.joint_states[i].name;
if(name == jointName){
Modified: pkg/trunk/highlevel/highlevel_controllers/src/MoveEndEffector.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/MoveEndEffector.cpp 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/highlevel/highlevel_controllers/src/MoveEndEffector.cpp 2008-10-14 00:48:39 UTC (rev 5314)
@@ -57,7 +57,7 @@
* @section topic ROS topics
*
* Subscribes to (name/type):
- * - @b "mechanism_state"/mechanism_control::MechanismState : The state of the robot joints and actuators
+ * - @b "mechanism_state"/robot_msgs::MechanismState : The state of the robot joints and actuators
* - @b "left/right_end_effector_goal"/pr2_msgs::MoveEndEffectorGoal: Where to move end effector
*
* Publishes to (name / type):
@@ -72,7 +72,7 @@
#include <HighlevelController.hh>
#include <pr2_mechanism_controllers/JointPosCmd.h>
-#include <mechanism_control/MechanismState.h>
+#include <robot_msgs/MechanismState.h>
#include <pr2_msgs/MoveEndEffectorState.h>
#include <pr2_msgs/MoveEndEffectorGoal.h>
#include <robot_srvs/KinematicPlanState.h>
@@ -98,7 +98,7 @@
* @brief Helper Method to obtain the joint value by name
* @return true if the joint is present, otherwise false
*/
- bool readJointValue(const mechanism_control::MechanismState& mechanismStateMsg, const std::string& name, double& value);
+ bool readJointValue(const robot_msgs::MechanismState& mechanismStateMsg, const std::string& name, double& value);
void handleArmConfigurationCallback();
void updateGoalMsg();
@@ -112,7 +112,7 @@
const std::string armCmdTopic;
const std::string kinematicModel;
- mechanism_control::MechanismState mechanismState;
+ robot_msgs::MechanismState mechanismState;
robot_srvs::KinematicPlanState::response plan;
unsigned int currentWaypoint; /*!< The waypoint in the plan that we are targetting */
@@ -121,7 +121,7 @@
};
-bool MoveEndEffector::readJointValue(const mechanism_control::MechanismState& mechanismStateMsg, const std::string& name, double& value){
+bool MoveEndEffector::readJointValue(const robot_msgs::MechanismState& mechanismStateMsg, const std::string& name, double& value){
for(unsigned int i = 0; i < mechanismStateMsg.get_joint_states_size(); i++){
const std::string& jointName = mechanismStateMsg.joint_states[i].name;
if(name == jointName){
Modified: pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
===================================================================
--- pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2008-10-14 00:48:39 UTC (rev 5314)
@@ -45,11 +45,11 @@
#include <mechanism_model/controller.h>
#include <misc_utils/realtime_publisher.h>
-#include "mechanism_control/ListControllerTypes.h"
-#include "mechanism_control/ListControllers.h"
-#include "mechanism_control/SpawnController.h"
-#include "mechanism_control/KillController.h"
-#include "mechanism_control/MechanismState.h"
+#include <robot_srvs/ListControllerTypes.h>
+#include <robot_srvs/ListControllers.h>
+#include <robot_srvs/SpawnController.h>
+#include <robot_srvs/KillController.h>
+#include <robot_msgs/MechanismState.h>
#include "rosTF/TransformArray.h"
@@ -106,25 +106,25 @@
void update(); // Must be realtime safe
- bool listControllerTypes(mechanism_control::ListControllerTypes::request &req,
- mechanism_control::ListControllerTypes::response &resp);
- bool listControllers(mechanism_control::ListControllers::request &req,
- mechanism_control::ListControllers::response &resp);
- bool spawnController(mechanism_control::SpawnController::request &req,
- mechanism_control::SpawnController::response &resp);
+ bool listControllerTypes(robot_srvs::ListControllerTypes::request &req,
+ robot_srvs::ListControllerTypes::response &resp);
+ bool listControllers(robot_srvs::ListControllers::request &req,
+ robot_srvs::ListControllers::response &resp);
+ bool spawnController(robot_srvs::SpawnController::request &req,
+ robot_srvs::SpawnController::response &resp);
private:
ros::node *node_;
- bool killController(mechanism_control::KillController::request &req,
- mechanism_control::KillController::response &resp);
+ bool killController(robot_srvs::KillController::request &req,
+ robot_srvs::KillController::response &resp);
MechanismControl *mc_;
static const double STATE_PUBLISHING_PERIOD = 0.01; // this translates to about 100Hz
const char* const mechanism_state_topic_;
- misc_utils::RealtimePublisher<mechanism_control::MechanismState> publisher_;
+ misc_utils::RealtimePublisher<robot_msgs::MechanismState> publisher_;
misc_utils::RealtimePublisher<rosTF::TransformArray> transform_publisher_;
};
Modified: pkg/trunk/mechanism/mechanism_control/manifest.xml
===================================================================
--- pkg/trunk/mechanism/mechanism_control/manifest.xml 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/manifest.xml 2008-10-14 00:48:39 UTC (rev 5314)
@@ -12,8 +12,10 @@
<depend package="misc_utils" />
<depend package="rospy" />
<depend package="tf" />
+<depend package="robot_msgs" />
+<depend package="robot_srvs" />
<export>
- <cpp cflags='-I${prefix}/include -I${prefix}/msg/cpp -I${prefix}/srv/cpp'
+ <cpp cflags='-I${prefix}/include'
lflags='-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lmechanism_control'/>
</export>
</package>
Modified: pkg/trunk/mechanism/mechanism_control/scripts/detect.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/detect.py 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/scripts/detect.py 2008-10-14 00:48:39 UTC (rev 5314)
@@ -2,10 +2,10 @@
import curses
import rostools
-rostools.update_path('mechanism_control')
+rostools.update_path('robot_msgs')
import sys, traceback, logging, rospy
-from mechanism_control.msg import MechanismState
+from robot_msgs.msg import MechanismState
NAME = 'joint_listener'
Modified: pkg/trunk/mechanism/mechanism_control/scripts/listen.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-10-14 00:48:39 UTC (rev 5314)
@@ -1,10 +1,10 @@
#!/usr/bin/env python
import rostools
-rostools.update_path('mechanism_control')
+rostools.update_path('robot_msgs')
import sys, traceback, logging, rospy
-from mechanism_control.msg import MechanismState
+from robot_msgs.msg import MechanismState
NAME = 'joint_listener'
Modified: pkg/trunk/mechanism/mechanism_control/scripts/writer.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/writer.py 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/scripts/writer.py 2008-10-14 00:48:39 UTC (rev 5314)
@@ -1,10 +1,10 @@
#!/usr/bin/env python
import rostools
-rostools.update_path('mechanism_control')
+rostools.update_path('robot_msgs')
import sys, traceback, logging, rospy
-from mechanism_control.msg import MechanismState
+from robot_msgs.msg import MechanismState
print "File name is: %s" %sys.argv[1]
filehandle = open(sys.argv[1],'w')
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control/mechanism.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control/mechanism.py 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control/mechanism.py 2008-10-14 00:48:39 UTC (rev 5314)
@@ -2,11 +2,11 @@
# Wrappers around the services provided by MechanismControlNode
import rostools
-rostools.update_path('mechanism_control')
+rostools.update_path('robot_srvs')
rostools.update_path('std_srvs')
import rospy, sys
-from mechanism_control.srv import *
+from robot_srvs.srv import *
import std_srvs.srv
def list_controller_types():
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-10-14 00:48:39 UTC (rev 5314)
@@ -206,7 +206,7 @@
node_->advertise_service("kill_controller", &MechanismControlNode::killController, this);
// Advertise topics
- node_->advertise<mechanism_control::MechanismState>(mechanism_state_topic_,10);
+ node_->advertise<robot_msgs::MechanismState>(mechanism_state_topic_,10);
node_->advertise<rosTF::TransformArray>("TransformArray");
node_->advertise<rostools::Time>("time");
}
@@ -246,7 +246,7 @@
assert(mc_->model_.joints_.size() == publisher_.msg_.get_joint_states_size());
for (unsigned int i = 0; i < mc_->model_.joints_.size(); ++i)
{
- mechanism_control::JointState *out = &publisher_.msg_.joint_states[i];
+ robot_msgs::JointState *out = &publisher_.msg_.joint_states[i];
mechanism::JointState *in = &mc_->state_->joint_states_[i];
out->name = mc_->model_.joints_[i]->name_;
out->position = in->position_;
@@ -257,7 +257,7 @@
for (unsigned int i = 0; i < mc_->hw_->actuators_.size(); ++i)
{
- mechanism_control::ActuatorState *out = &publisher_.msg_.actuator_states[i];
+ robot_msgs::ActuatorState *out = &publisher_.msg_.actuator_states[i];
ActuatorState *in = &mc_->hw_->actuators_[i]->state_;
out->name = mc_->hw_->actuators_[i]->name_;
out->encoder_count = in->encoder_count_;
@@ -318,8 +318,8 @@
}
bool MechanismControlNode::listControllerTypes(
- mechanism_control::ListControllerTypes::request &req,
- mechanism_control::ListControllerTypes::response &resp)
+ robot_srvs::ListControllerTypes::request &req,
+ robot_srvs::ListControllerTypes::response &resp)
{
std::vector<std::string> types;
@@ -330,8 +330,8 @@
}
bool MechanismControlNode::spawnController(
- mechanism_control::SpawnController::request &req,
- mechanism_control::SpawnController::response &resp)
+ robot_srvs::SpawnController::request &req,
+ robot_srvs::SpawnController::response &resp)
{
TiXmlDocument doc;
doc.Parse(req.xml_config.c_str());
@@ -375,8 +375,8 @@
}
bool MechanismControlNode::listControllers(
- mechanism_control::ListControllers::request &req,
- mechanism_control::ListControllers::response &resp)
+ robot_srvs::ListControllers::request &req,
+ robot_srvs::ListControllers::response &resp)
{
std::vector<std::string> controllers;
@@ -387,8 +387,8 @@
}
bool MechanismControlNode::killController(
- mechanism_control::KillController::request &req,
- mechanism_control::KillController::response &resp)
+ robot_srvs::KillController::request &req,
+ robot_srvs::KillController::response &resp)
{
resp.ok = mc_->killController(req.name);
return true;
Modified: pkg/trunk/mechanism/mechanism_control/test/ms_publisher_test.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/test/ms_publisher_test.cpp 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control/test/ms_publisher_test.cpp 2008-10-14 00:48:39 UTC (rev 5314)
@@ -26,13 +26,13 @@
//////////////////////////////////////////////////////////////////////////////
#include "ros/node.h"
-#include "mechanism_control/MechanismState.h"
-#include "mechanism_control/ActuatorState.h"
-#include "mechanism_control/JointState.h"
+#include "robot_msgs/MechanismState.h"
+#include "robot_msgs/ActuatorState.h"
+#include "robot_msgs/JointState.h"
void publish(ros::node *node)
{
- mechanism_control::MechanismState mechanism_state;
+ robot_msgs::MechanismState mechanism_state;
mechanism_state.set_joint_states_size(250);
mechanism_state.set_actuator_states_size(260);
@@ -41,7 +41,7 @@
{
for (unsigned int i = 0; i < mechanism_state.get_joint_states_size(); ++i)
{
- mechanism_control::JointState *out = mechanism_state.joint_states + i;
+ robot_msgs::JointState *out = mechanism_state.joint_states + i;
out->name = "jointstate";
out->position = 1.0;
out->velocity = 1.0;
@@ -51,7 +51,7 @@
for (unsigned int i = 0; i < mechanism_state.get_actuator_states_size(); ++i)
{
- mechanism_control::ActuatorState *out = mechanism_state.actuator_states + i;
+ robot_msgs::ActuatorState *out = mechanism_state.actuator_states + i;
out->name = "actuatorstate";
out->encoder_count = i;
out->position = 1.0;
@@ -81,7 +81,7 @@
ros::init(argc, argv);
ros::node *node = new ros::node("mechanism_control");
- node->advertise<mechanism_control::MechanismState>("mechanism_state");
+ node->advertise<robot_msgs::MechanismState>("mechanism_state");
while (1) {
std::cout << "publish" << std::endl;
publish(node);
Modified: pkg/trunk/mechanism/mechanism_control_rt/manifest.xml
===================================================================
--- pkg/trunk/mechanism/mechanism_control_rt/manifest.xml 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/mechanism/mechanism_control_rt/manifest.xml 2008-10-14 00:48:39 UTC (rev 5314)
@@ -11,10 +11,12 @@
<depend package="mechanism_model"/>
<depend package="misc_utils" />
<depend package="rospy" />
-<depend package="rosTF" />
+<depend package="tf" />
+<depend package="robot_msgs" />
+<depend package="robot_srvs" />
<depend package="xenomai" />
<export>
- <cpp cflags='-I${prefix}/include -I${prefix}/msg/cpp -I${prefix}/srv/cpp'
+ <cpp cflags='-I${prefix}/include'
lflags='-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lmechanism_control_rt'/>
</export>
</package>
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-10-14 00:48:39 UTC (rev 5314)
@@ -51,7 +51,7 @@
#include <rosTF/rosTF.h>
#include <cmath>
-#include <mechanism_control/MechanismState.h>
+#include <robot_msgs/MechanismState.h>
/** Main namespace */
namespace planning_node_util
@@ -297,7 +297,7 @@
std_msgs::RobotBase2DOdom m_localizedPose;
bool m_haveBasePos;
- mechanism_control::MechanismState m_mechanismState; // this message should be moved to robot_msgs
+ robot_msgs::MechanismState m_mechanismState; // this message should be moved to robot_msgs
bool m_haveMechanismState;
robot_desc::URDF *m_urdf;
Modified: pkg/trunk/pr2_msgs/manifest.xml
===================================================================
--- pkg/trunk/pr2_msgs/manifest.xml 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/pr2_msgs/manifest.xml 2008-10-14 00:48:39 UTC (rev 5314)
@@ -10,7 +10,6 @@
<logo>http://www.willowgarage.com/files/willowgarage/robot10.jpg</logo>
<depend package="robot_msgs"/>
<depend package="std_msgs"/>
- <depend package="mechanism_control"/>
<export>
<cpp cflags="-I${prefix}/msg/cpp"/>
</export>
Modified: pkg/trunk/pr2_msgs/msg/MoveArmGoal.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/MoveArmGoal.msg 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/pr2_msgs/msg/MoveArmGoal.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -1,6 +1,6 @@
Header header
# The desired joint configuratin
-mechanism_control/JointState[] configuration
+robot_msgs/JointState[] configuration
# Indicate if the goal is being enabled or disabled
byte enable
Modified: pkg/trunk/pr2_msgs/msg/MoveArmState.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/MoveArmState.msg 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/pr2_msgs/msg/MoveArmState.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -6,6 +6,6 @@
#Did we actually successfully arrive at the goal?
byte done
#Current arm configuration
-mechanism_control/JointState[] configuration
+robot_msgs/JointState[] configuration
#Goal arm configuration
-mechanism_control/JointState[] goal
+robot_msgs/JointState[] goal
Modified: pkg/trunk/pr2_msgs/msg/MoveEndEffectorGoal.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/MoveEndEffectorGoal.msg 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/pr2_msgs/msg/MoveEndEffectorGoal.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -1,6 +1,6 @@
Header header
# The desired joint configuratin
-mechanism_control/JointState[] configuration
+robot_msgs/JointState[] configuration
# Indicate if the goal is being enabled or disabled
byte enable
Modified: pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg 2008-10-14 00:45:55 UTC (rev 5313)
+++ pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -6,6 +6,6 @@
#Did we actually successfully arrive at the goal?
byte done
#Current arm configuration
-mechanism_control/JointState[] configuration
+robot_msgs/JointState[] configuration
#Goal arm configuration
-mechanism_control/JointState[] goal
+robot_msgs/JointState[] goal
Copied: pkg/trunk/robot_msgs/msg/ActuatorState.msg (from rev 5297, pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg)
===================================================================
--- pkg/trunk/robot_msgs/msg/ActuatorState.msg (rev 0)
+++ pkg/trunk/robot_msgs/msg/ActuatorState.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,20 @@
+string name
+int32 encoder_count
+float64 position
+float64 timestamp
+float64 encoder_velocity
+float64 velocity
+byte calibration_reading
+float64 last_calibration_high_transition
+float64 last_calibration_low_transition
+byte is_enabled
+byte run_stop_hit
+float64 last_requested_current
+float64 last_commanded_current
+float64 last_measured_current
+float64 last_requested_effort
+float64 last_commanded_effort
+float64 last_measured_effort
+float64 motor_voltage
+int32 num_encoder_errors
+
Copied: pkg/trunk/robot_msgs/msg/JointState.msg (from rev 5297, pkg/trunk/mechanism/mechanism_control/msg/JointState.msg)
===================================================================
--- pkg/trunk/robot_msgs/msg/JointState.msg (rev 0)
+++ pkg/trunk/robot_msgs/msg/JointState.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,5 @@
+string name
+float64 position
+float64 velocity
+float64 applied_effort
+float64 commanded_effort
Copied: pkg/trunk/robot_msgs/msg/MechanismState.msg (from rev 5297, pkg/trunk/mechanism/mechanism_control/msg/MechanismState.msg)
===================================================================
--- pkg/trunk/robot_msgs/msg/MechanismState.msg (rev 0)
+++ pkg/trunk/robot_msgs/msg/MechanismState.msg 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,4 @@
+Header header
+float64 time
+ActuatorState[] actuator_states
+JointState[] joint_states
Copied: pkg/trunk/robot_srvs/srv/KillController.srv (from rev 5297, pkg/trunk/mechanism/mechanism_control/srv/KillController.srv)
===================================================================
--- pkg/trunk/robot_srvs/srv/KillController.srv (rev 0)
+++ pkg/trunk/robot_srvs/srv/KillController.srv 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,3 @@
+string name
+---
+byte ok
Copied: pkg/trunk/robot_srvs/srv/ListControllerTypes.srv (from rev 5297, pkg/trunk/mechanism/mechanism_control/srv/ListControllerTypes.srv)
===================================================================
--- pkg/trunk/robot_srvs/srv/ListControllerTypes.srv (rev 0)
+++ pkg/trunk/robot_srvs/srv/ListControllerTypes.srv 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,2 @@
+---
+string[] types
\ No newline at end of file
Copied: pkg/trunk/robot_srvs/srv/ListControllers.srv (from rev 5297, pkg/trunk/mechanism/mechanism_control/srv/ListControllers.srv)
===================================================================
--- pkg/trunk/robot_srvs/srv/ListControllers.srv (rev 0)
+++ pkg/trunk/robot_srvs/srv/ListControllers.srv 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,2 @@
+---
+string[] controllers
Copied: pkg/trunk/robot_srvs/srv/SpawnController.srv (from rev 5297, pkg/trunk/mechanism/mechanism_control/srv/SpawnController.srv)
===================================================================
--- pkg/trunk/robot_srvs/srv/SpawnController.srv (rev 0)
+++ pkg/trunk/robot_srvs/srv/SpawnController.srv 2008-10-14 00:48:39 UTC (rev 5314)
@@ -0,0 +1,4 @@
+string xml_config
+---
+byte[] ok
+string[] name
\ No newline at end of file
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|