|
From: <mee...@us...> - 2009-09-01 01:17:37
|
Revision: 23437
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23437&view=rev
Author: meeussen
Date: 2009-09-01 00:35:02 +0000 (Tue, 01 Sep 2009)
Log Message:
-----------
add pr2_mechanism:: namespace to pr2_mechanism_controller, pr2_mechanism_model and pr2_hardware_interface
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_kinematics.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_position_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_base_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_odometry.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_kinematics.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_position_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_base_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/test/test_base_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_pose_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_twist_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_ud_calibration_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/trigger_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_twist_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_effort_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_ud_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/trigger_controller.cpp
pkg/trunk/sandbox/dallas_controller/include/dallas_controller/dallas_controller.h
pkg/trunk/sandbox/dallas_controller/src/dallas_controller.cpp
pkg/trunk/sandbox/dynamics_estimation/include/dynamics_estimation/dynamics_estimation_node.h
pkg/trunk/sandbox/dynamics_estimation/src/dynamics_estimation_node.cpp
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/arm_trajectory_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/base_position_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_hybrid_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_pose_twist_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_spline_trajectory_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_tff_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_trajectory_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/cartesian_twist_controller_ik.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/caster_calibration_controller_effort.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/caster_controller_effort.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/endeffector_constraint_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/head_servoing_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_autotuner.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_blind_calibration_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_calibration_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_chain_constraint_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_chain_sine_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_inverse_dynamics_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_limit_calibration_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_pd_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_position_smoothing_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_trajectory_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/laser_scanner_qualification.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/pid_position_velocity_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/plug_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/pr2_gripper_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/probe.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/trajectory_controller.h
pkg/trunk/sandbox/experimental_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/base_position_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/cartesian_hybrid_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/cartesian_pose_twist_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/cartesian_spline_trajectory_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/cartesian_tff_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/cartesian_trajectory_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/cartesian_twist_controller_ik.cpp
pkg/trunk/sandbox/experimental_controllers/src/caster_calibration_controller_effort.cpp
pkg/trunk/sandbox/experimental_controllers/src/caster_controller_effort.cpp
pkg/trunk/sandbox/experimental_controllers/src/endeffector_constraint_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/head_servoing_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_autotuner.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_blind_calibration_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_calibration_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_chain_constraint_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_chain_sine_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_inverse_dynamics_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_limit_calibration_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_pd_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_position_smoothing_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_trajectory_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/laser_scanner_qualification.cpp
pkg/trunk/sandbox/experimental_controllers/src/pid_position_velocity_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/plug_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/pr2_gripper_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/probe.cpp
pkg/trunk/sandbox/experimental_controllers/src/trajectory_controller.cpp
pkg/trunk/sandbox/mechanism_control_test/include/mechanism_controller_test/null_hardware.h
pkg/trunk/sandbox/mechanism_control_test/src/mechanism_controller_test.cpp
pkg/trunk/sandbox/mechanism_control_test/src/null_hardware.cpp
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/checkout_controller.h
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hold_set_controller.h
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/sine_sweep_controller.h
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/src/checkout_controller.cpp
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/src/hold_set_controller.cpp
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/src/hysteresis_controller.cpp
pkg/trunk/sandbox/qualification_controllers/joint_qualification_controllers/src/sine_sweep_controller.cpp
pkg/trunk/sandbox/rtt_controller/manifest.xml
pkg/trunk/sandbox/rtt_controller/src/pr2_etherCAT_component.cpp
pkg/trunk/sandbox/trajectory_controllers/include/trajectory_controllers/joint_trajectory_controller2.h
pkg/trunk/sandbox/trajectory_controllers/src/joint_trajectory_controller2.cpp
pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_device.h
pkg/trunk/stacks/pr2_mechanism/pr2_controller_interface/include/pr2_controller_interface/controller.h
pkg/trunk/stacks/pr2_mechanism/pr2_hardware_interface/include/pr2_hardware_interface/hardware_interface.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/include/pr2_mechanism_control/mechanism_control.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/include/pr2_mechanism_control/recorder.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/src/mechanism_control.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_control/src/recorder.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/chain.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/gripper_transmission.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/joint.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/pr2_gripper_transmission.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/robot.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/simple_transmission.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/transmission.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/wrist_transmission.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/chain.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/gripper_transmission.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/joint.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/nonlinear_transmission.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/pr2_gripper_transmission.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/robot.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/simple_transmission.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/wrist_transmission.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/test/test_chain.cpp
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/transmission_plugins.xml
pkg/trunk/stacks/pr2_simulator/gazebo_plugin/include/gazebo_plugin/gazebo_mechanism_control.h
pkg/trunk/stacks/pr2_simulator/gazebo_plugin/src/gazebo_mechanism_control.cpp
Removed Paths:
-------------
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/include/pr2_mechanism_model/link.h
pkg/trunk/stacks/pr2_mechanism/pr2_mechanism_model/src/link.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_kinematics.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_kinematics.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_kinematics.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -59,7 +59,7 @@
/*!
* \brief JointState for this wheel joint
*/
- mechanism::JointState *joint_;
+ pr2_mechanism::JointState *joint_;
/*!
* \brief default offset from the parent caster before any transformations
@@ -127,8 +127,8 @@
* @param robot_state The robot's current state
* @param config Tiny xml element pointing to this wheel
*/
-// void initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
- bool init(mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name);
+// void initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name);
/*!
* \brief Computes 2d postion of the wheel relative to the center of the base
@@ -146,7 +146,7 @@
/*!
* \brief JointState for this caster joint
*/
- mechanism::JointState *joint_;
+ pr2_mechanism::JointState *joint_;
/*!
* \brief offset from the center of the base
@@ -220,8 +220,8 @@
* @param robot_state The robot's current state
* @param config Tiny xml element pointing to this caster
*/
-// void initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
- bool init(mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name);
+// void initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name);
};
/*! \class
@@ -237,8 +237,8 @@
* @param config Tiny xml element pointing to its controller
* @return Successful init
*/
-// bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
- bool init(mechanism::RobotState *robot_state, const ros::NodeHandle &node);
+// bool initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node);
/*!
* \brief Computes 2d postion of every wheel relative to the center of the base
@@ -256,7 +256,7 @@
/*!
* \brief remembers everything about the state of the robot
*/
- mechanism::RobotState *robot_state_;
+ pr2_mechanism::RobotState *robot_state_;
/*!
* \brief number of wheels connected to the base
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -47,8 +47,8 @@
CasterCalibrationController();
~CasterCalibrationController();
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ virtual bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ virtual bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
/*!
@@ -66,7 +66,7 @@
protected:
ros::NodeHandle node_;
- mechanism::RobotState *robot_;
+ pr2_mechanism::RobotState *robot_;
enum { INITIALIZED, BEGINNING, MOVING, CALIBRATED };
int state_;
@@ -74,9 +74,9 @@
double search_velocity_;
bool original_switch_state_;
- Actuator *actuator_;
- mechanism::JointState *joint_, *wheel_l_joint_, *wheel_r_joint_;
- mechanism::Transmission *transmission_;
+ pr2_mechanism::Actuator *actuator_;
+ pr2_mechanism::JointState *joint_, *wheel_l_joint_, *wheel_r_joint_;
+ pr2_mechanism::Transmission *transmission_;
controller::CasterController cc_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -61,12 +61,12 @@
CasterController();
~CasterController();
- bool init(mechanism::RobotState *robot_state,
+ bool init(pr2_mechanism::RobotState *robot_state,
const std::string &caster_joint,
const std::string &wheel_l_joint, const std::string &wheel_r_joint,
const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid);
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
void update();
@@ -76,7 +76,7 @@
double getSteerPosition() { return caster_->position_; }
double getSteerVelocity() { return caster_->velocity_; }
- mechanism::JointState *caster_;
+ pr2_mechanism::JointState *caster_;
private:
ros::NodeHandle node_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -50,8 +50,8 @@
GripperCalibrationController();
~GripperCalibrationController();
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ virtual bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ virtual bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
virtual void update();
@@ -68,13 +68,13 @@
int count_;
ros::NodeHandle node_;
- mechanism::RobotState *robot_;
+ pr2_mechanism::RobotState *robot_;
ros::Time last_publish_time_;
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
double search_velocity_;
- Actuator *actuator_;
- mechanism::JointState *joint_;
+ pr2_mechanism::Actuator *actuator_;
+ pr2_mechanism::JointState *joint_;
double init_time;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_position_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_position_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_position_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -58,7 +58,7 @@
HeadPositionController();
~HeadPositionController();
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
bool starting();
void update();
@@ -70,7 +70,7 @@
ros::NodeHandle node_;
std::string pan_link_name_, tilt_link_name_;
- mechanism::RobotState *robot_state_;
+ pr2_mechanism::RobotState *robot_state_;
ros::Subscriber sub_command_;
void command(const sensor_msgs::JointStateConstPtr& command_msg);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -68,8 +68,8 @@
LaserScannerTrajController() ;
~LaserScannerTrajController() ;
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
virtual void update() ;
@@ -93,16 +93,16 @@
//void initDErrorFilter(double f) ; // Initializes d_error_filter using a smoothing factor
- mechanism::RobotState *robot_ ;
- mechanism::JointState *joint_state_ ; // Need this to check the calibrated flag on the joint
+ pr2_mechanism::RobotState *robot_ ;
+ pr2_mechanism::JointState *joint_state_ ; // Need this to check the calibrated flag on the joint
boost::mutex traj_lock_ ; // Mutex for traj_
trajectory::Trajectory traj_ ; // Stores the current trajectory being executed
//boost::mutex track_link_lock_ ;
//bool track_link_enabled_ ;
- //mechanism::LinkState* target_link_ ;
- //mechanism::LinkState* mount_link_ ;
+ //pr2_mechanism::LinkState* target_link_ ;
+ //pr2_mechanism::LinkState* mount_link_ ;
tf::Vector3 track_point_ ;
//JointPositionSmoothController joint_position_controller_ ; // The PID position controller that is doing all the under-the-hood controls stuff
@@ -133,8 +133,8 @@
void update() ;
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config) ;
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config) ;
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
// Message Callbacks
void setPeriodicCmd() ;
@@ -149,7 +149,7 @@
private:
ros::Node *node_ ;
LaserScannerTrajController c_ ;
- mechanism::RobotState *robot_ ;
+ pr2_mechanism::RobotState *robot_ ;
std::string service_prefix_ ;
int prev_profile_segment_ ; //!< The segment in the current profile when update() was last called
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_base_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_base_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -72,7 +72,7 @@
*/
bool starting();
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
/*!
* \brief Loads controller's information from the xml description file and param server
@@ -80,7 +80,7 @@
* @param config Tiny xml element pointing to this controller
* @return Successful init
*/
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
/*
* \brief callback function for setting the desired velocity using a topic
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_odometry.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_odometry.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/pr2_odometry.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -73,7 +73,7 @@
* @param config Tiny xml element pointing to this controller
* @return Successful init
*/
- bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
+ bool initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config);
/*!
* \brief Initializes and loads odometry information from the param server
@@ -81,7 +81,7 @@
* @param config Tiny xml element pointing to this controller
* @return Successful init
*/
- bool init(mechanism::RobotState *robot_state, const ros::NodeHandle &node);
+ bool init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node);
/*
* \brief The starting method is called by the realtime thread just before
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -56,8 +56,8 @@
WristCalibrationController();
~WristCalibrationController();
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ virtual bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ virtual bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
/*!
* \brief Issues commands to the joint. Should be called at regular intervals
@@ -76,7 +76,7 @@
enum { INITIALIZED, BEGINNING, MOVING_FLEX, MOVING_ROLL, CALIBRATED };
int state_;
- mechanism::RobotState *robot_;
+ pr2_mechanism::RobotState *robot_;
ros::NodeHandle node_;
ros::Time last_publish_time_;
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
@@ -90,9 +90,9 @@
double prev_actuator_l_position_, prev_actuator_r_position_;
- Actuator *actuator_l_, *actuator_r_;
- mechanism::JointState *flex_joint_, *roll_joint_;
- mechanism::Transmission *transmission_;
+ pr2_mechanism::Actuator *actuator_l_, *actuator_r_;
+ pr2_mechanism::JointState *flex_joint_, *roll_joint_;
+ pr2_mechanism::Transmission *transmission_;
controller::JointVelocityController vc_flex_, vc_roll_;
};
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_kinematics.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_kinematics.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_kinematics.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -40,7 +40,7 @@
using namespace controller;
-bool Wheel::init(mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name)
+bool Wheel::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name)
{
wheel_stuck_ = 0;
direction_multiplier_ = 1;
@@ -72,7 +72,7 @@
return true;
}
-bool Caster::init(mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name)
+bool Caster::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node, std::string link_name)
{
caster_stuck_ = 0;
caster_speed_ = 0;
@@ -118,7 +118,7 @@
return true;
}
-bool BaseKinematics::init(mechanism::RobotState *robot_state, const ros::NodeHandle &node)
+bool BaseKinematics::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node)
{
std::string caster_names_string;
std::vector<std::string> caster_names;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -48,7 +48,7 @@
{
}
-bool CasterCalibrationController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool CasterCalibrationController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
// This method is gross and ugly and should change (and the xml
// config format along with it)
@@ -101,7 +101,7 @@
return true;
}
-bool CasterCalibrationController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool CasterCalibrationController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
node_ = n;
robot_ = robot;
@@ -217,10 +217,10 @@
bool switch_state_ = actuator_->state_.calibration_reading_;
if (switch_state_ != original_switch_state_)
{
- Actuator a;
- mechanism::JointState j;
- std::vector<Actuator*> fake_a;
- std::vector<mechanism::JointState*> fake_j;
+ pr2_mechanism::Actuator a;
+ pr2_mechanism::JointState j;
+ std::vector<pr2_mechanism::Actuator*> fake_a;
+ std::vector<pr2_mechanism::JointState*> fake_j;
fake_a.push_back(&a);
fake_j.push_back(&j);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -51,7 +51,7 @@
}
bool CasterController::init(
- mechanism::RobotState *robot,
+ pr2_mechanism::RobotState *robot,
const std::string &caster_joint,
const std::string &wheel_l_joint, const std::string &wheel_r_joint,
const control_toolbox::Pid &caster_pid, const control_toolbox::Pid &wheel_pid)
@@ -73,7 +73,7 @@
return true;
}
-bool CasterController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool CasterController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
TiXmlElement *jel = config->FirstChildElement("joints");
if (!jel)
@@ -122,7 +122,7 @@
return init(robot, caster_joint, wheel_l_joint, wheel_r_joint, caster_pid, wheel_pid);
}
-bool CasterController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool CasterController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
node_ = n;
assert(robot);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -53,7 +53,7 @@
{
}
-bool GripperCalibrationController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool GripperCalibrationController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
assert(robot);
assert(config);
@@ -106,7 +106,7 @@
return true;
}
-bool GripperCalibrationController::init(mechanism::RobotState *robot,
+bool GripperCalibrationController::init(pr2_mechanism::RobotState *robot,
const ros::NodeHandle &n)
{
assert(robot);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_position_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_position_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -57,7 +57,7 @@
}
-bool HeadPositionController::init(mechanism::RobotState *robot_state, const ros::NodeHandle &n)
+bool HeadPositionController::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &n)
{
node_ = n;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -56,7 +56,7 @@
}
-bool LaserScannerTrajController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool LaserScannerTrajController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
if (!robot || !config)
return false ;
@@ -163,7 +163,7 @@
return true ;
}
-bool LaserScannerTrajController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool LaserScannerTrajController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
std::string xml;
if (!n.getParam("xml", xml))
@@ -504,7 +504,7 @@
}
}
-bool LaserScannerTrajControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool LaserScannerTrajControllerNode::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
robot_ = robot ; // Need robot in order to grab hardware time
@@ -535,7 +535,7 @@
return true ;
}
-bool LaserScannerTrajControllerNode::init(mechanism::RobotState *robot,
+bool LaserScannerTrajControllerNode::init(pr2_mechanism::RobotState *robot,
const ros::NodeHandle &n)
{
std::string xml;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_base_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_base_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -70,7 +70,7 @@
{
}
-bool Pr2BaseController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool Pr2BaseController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
if(!base_kin_.init(robot,n))
return false;
@@ -151,7 +151,7 @@
return true;
}
-bool Pr2BaseController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool Pr2BaseController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
// base_kin_.initXml(robot, config);
return init(robot, ros::NodeHandle(config->Attribute("name")));
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_odometry.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -50,7 +50,7 @@
{
}
-bool Pr2Odometry::init(mechanism::RobotState *robot_state, const ros::NodeHandle &node)
+bool Pr2Odometry::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &node)
{
node_ = node;
node.param("odometer/distance", odometer_distance_, 0.0);
@@ -100,7 +100,7 @@
return true;
}
-bool Pr2Odometry::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
+bool Pr2Odometry::initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config)
{
return init(robot_state,ros::NodeHandle(config->Attribute("name")));
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -48,7 +48,7 @@
{
}
-bool WristCalibrationController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool WristCalibrationController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
assert(robot);
assert(config);
@@ -131,7 +131,7 @@
return true;
}
-bool WristCalibrationController::init(mechanism::RobotState *robot,
+bool WristCalibrationController::init(pr2_mechanism::RobotState *robot,
const ros::NodeHandle &n)
{
assert(robot);
@@ -311,17 +311,17 @@
// optical switches were hit. Now we compute the actuator
// positions when the joints should be at 0.
- const int LEFT_MOTOR = mechanism::WristTransmission::LEFT_MOTOR;
- const int RIGHT_MOTOR = mechanism::WristTransmission::RIGHT_MOTOR;
- const int FLEX_JOINT = mechanism::WristTransmission::FLEX_JOINT;
- const int ROLL_JOINT = mechanism::WristTransmission::ROLL_JOINT;
+ const int LEFT_MOTOR = pr2_mechanism::WristTransmission::LEFT_MOTOR;
+ const int RIGHT_MOTOR = pr2_mechanism::WristTransmission::RIGHT_MOTOR;
+ const int FLEX_JOINT = pr2_mechanism::WristTransmission::FLEX_JOINT;
+ const int ROLL_JOINT = pr2_mechanism::WristTransmission::ROLL_JOINT;
// Sets up the data structures for passing joint and actuator
// positions through the transmission.
- Actuator fake_as_mem[2]; // This way we don't need to delete the objects later
- mechanism::JointState fake_js_mem[2];
- std::vector<Actuator*> fake_as;
- std::vector<mechanism::JointState*> fake_js;
+ pr2_mechanism::Actuator fake_as_mem[2]; // This way we don't need to delete the objects later
+ pr2_mechanism::JointState fake_js_mem[2];
+ std::vector<pr2_mechanism::Actuator*> fake_as;
+ std::vector<pr2_mechanism::JointState*> fake_js;
fake_as.push_back(&fake_as_mem[0]);
fake_as.push_back(&fake_as_mem[1]);
fake_js.push_back(&fake_js_mem[0]);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/test/test_base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/test/test_base_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/test/test_base_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -17,7 +17,7 @@
/*********** Create the robot model ****************/
- mechanism::Robot *robot_model = new mechanism::Robot;
+ pr2_mechanism::Robot *robot_model = new pr2_mechanism::Robot;
controller::BaseControllerNode bc;
HardwareInterface hw(0);
robot_model->hw_ = &hw;
@@ -33,7 +33,7 @@
TiXmlElement *root = xml.FirstChildElement("robot");
urdf::normalizeXml(root);
robot_model->initXml(root);
- mechanism::RobotState *robot_state = new mechanism::RobotState(robot_model, &hw);
+ pr2_mechanism::RobotState *robot_state = new pr2_mechanism::RobotState(robot_model, &hw);
/*********** Load the controller file ************/
@@ -106,7 +106,7 @@
TEST (BaseControllerTests, loadXML)
{
- mechanism::Robot *robot = new mechanism::Robot("r2d2");
+ pr2_mechanism::Robot *robot = new pr2_mechanism::Robot("r2d2");
controller::BaseController bc;
const string xml_controller_file = "controller_base.xml";
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_pose_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_pose_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_pose_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -91,7 +91,7 @@
CartesianPoseController();
~CartesianPoseController();
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
bool starting();
void update();
@@ -115,8 +115,8 @@
ros::Time last_time_;
// robot structure
- mechanism::RobotState *robot_state_;
- mechanism::Chain chain_;
+ pr2_mechanism::RobotState *robot_state_;
+ pr2_mechanism::Chain chain_;
// pid controllers
std::vector<control_toolbox::Pid> pid_controller_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_twist_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_twist_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_twist_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -81,8 +81,8 @@
CartesianTwistController();
~CartesianTwistController();
- bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
bool starting();
void update();
@@ -104,8 +104,8 @@
std::vector<control_toolbox::Pid> fb_pid_controller_;
// robot description
- mechanism::RobotState *robot_state_;
- mechanism::Chain chain_;
+ pr2_mechanism::RobotState *robot_state_;
+ pr2_mechanism::Chain chain_;
// kdl stuff for kinematics
KDL::Chain kdl_chain_;
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-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -75,8 +75,8 @@
CartesianWrenchController();
~CartesianWrenchController();
- bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
bool starting();
void update();
@@ -88,8 +88,8 @@
ros::NodeHandle node_;
ros::Subscriber sub_command_;
void command(const geometry_msgs::WrenchConstPtr& wrench_msg);
- mechanism::RobotState *robot_state_;
- mechanism::Chain chain_;
+ pr2_mechanism::RobotState *robot_state_;
+ pr2_mechanism::Chain chain_;
KDL::Chain kdl_chain_;
boost::scoped_ptr<KDL::ChainJntToJacSolver> jnt_to_jac_solver_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -67,19 +67,19 @@
JointEffortController();
~JointEffortController();
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const std::string &joint_name);
- virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const std::string &joint_name);
+ virtual bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
virtual bool starting() { command_ = 0.0; return true; }
virtual void update();
- mechanism::JointState *joint_state_;
+ pr2_mechanism::JointState *joint_state_;
double command_;
private:
- mechanism::RobotState *robot_;
+ pr2_mechanism::RobotState *robot_;
ros::NodeHandle node_;
ros::Subscriber sub_command_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -78,9 +78,9 @@
JointPositionController();
~JointPositionController();
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const std::string &joint_name,const control_toolbox::Pid &pid);
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const std::string &joint_name,const control_toolbox::Pid &pid);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -108,14 +108,14 @@
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
std::string getJointName();
- mechanism::JointState *joint_state_; /**< Joint we're controlling. */
+ pr2_mechanism::JointState *joint_state_; /**< Joint we're controlling. */
ros::Duration dt_;
double command_; /**< Last commanded position. */
private:
int loop_count_;
bool initialized_;
- mechanism::RobotState *robot_; /**< Pointer to robot structure. */
+ pr2_mechanism::RobotState *robot_; /**< Pointer to robot structure. */
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
ros::Time last_time_; /**< Last time stamp of update. */
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_ud_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_ud_calibration_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_ud_calibration_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -50,8 +50,8 @@
JointUDCalibrationController();
virtual ~JointUDCalibrationController();
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ virtual bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ virtual bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
virtual void update();
@@ -64,7 +64,7 @@
protected:
- mechanism::RobotState* robot_;
+ pr2_mechanism::RobotState* robot_;
ros::NodeHandle node_;
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
ros::Time last_publish_time_;
@@ -76,9 +76,9 @@
double search_velocity_;
bool original_switch_state_;
- Actuator *actuator_;
- mechanism::JointState *joint_;
- mechanism::Transmission *transmission_;
+ pr2_mechanism::Actuator *actuator_;
+ pr2_mechanism::JointState *joint_;
+ pr2_mechanism::Transmission *transmission_;
controller::JointVelocityController vc_;
};
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -90,9 +90,9 @@
* \param joint_name Name of joint we want to control.
* \param *robot The robot.
*/
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- bool init(mechanism::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid);
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config);
+ bool init(pr2_mechanism::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -121,13 +121,13 @@
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
std::string getJointName();
- mechanism::JointState *joint_state_; /**< Joint we're controlling. */
+ pr2_mechanism::JointState *joint_state_; /**< Joint we're controlling. */
ros::Duration dt_;
double command_; /**< Last commanded position. */
private:
ros::NodeHandle node_;
- mechanism::RobotState *robot_; /**< Pointer to robot structure. */
+ pr2_mechanism::RobotState *robot_; /**< Pointer to robot structure. */
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
ros::Time last_time_; /**< Last time stamp of update. */
int loop_count_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/trigger_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/trigger_controller.h 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/trigger_controller.h 2009-09-01 00:35:02 UTC (rev 23437)
@@ -66,7 +66,7 @@
void update();
- bool init(mechanism::RobotState *robot, const ros::NodeHandle &n);
+ bool init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n);
/**
* \brief Convert time to an unrolled phase (in cycles).
@@ -226,8 +226,8 @@
bool setWaveformSrv(trigger_configuration &req,
robot_mechanism_controllers::SetWaveform::Response &resp);
- mechanism::RobotState * robot_;
- ActuatorCommand *actuator_command_;
+ pr2_mechanism::RobotState * robot_;
+ pr2_mechanism::ActuatorCommand *actuator_command_;
double prev_tick_;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_pose_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -60,7 +60,7 @@
{}
-bool CartesianPoseController::init(mechanism::RobotState *robot_state, const ros::NodeHandle &n)
+bool CartesianPoseController::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &n)
{
node_ = n;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_twist_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_twist_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_twist_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -58,7 +58,7 @@
-bool CartesianTwistController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
+bool CartesianTwistController::initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config)
{
// get the controller name from xml file
std::string controller_name = config->Attribute("name") ? config->Attribute("name") : "";
@@ -70,7 +70,7 @@
return init(robot_state, ros::NodeHandle(controller_name));
}
-bool CartesianTwistController::init(mechanism::RobotState *robot_state, const ros::NodeHandle &n)
+bool CartesianTwistController::init(pr2_mechanism::RobotState *robot_state, const ros::NodeHandle &n)
{
node_ = n;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -57,7 +57,7 @@
-bool CartesianWrenchController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
+bool CartesianWrenchController::initXml(pr2_mechanism::RobotState *robot_state, TiXmlElement *config)
{
// get the controller name from xml file
std::string controller_name = config->Attribute("name") ? config->Attribute("name") : "";
@@ -69,7 +69,7 @@
return init(robot_state, ros::NodeHandle(controller_name));
}
-bool CartesianWrenchController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool CartesianWrenchController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
// test if we got robot pointer
assert(robot);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_effort_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_effort_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_effort_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -49,7 +49,7 @@
sub_command_.shutdown();
}
-bool JointEffortController::init(mechanism::RobotState *robot, const std::string &joint_name)
+bool JointEffortController::init(pr2_mechanism::RobotState *robot, const std::string &joint_name)
{
if (!robot)
{
@@ -69,7 +69,7 @@
return true;
}
-bool JointEffortController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool JointEffortController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
if (!robot)
{
@@ -91,7 +91,7 @@
}
-bool JointEffortController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool JointEffortController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
assert(robot);
node_ = n;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -52,7 +52,7 @@
{
}
-bool JointPositionController::init(mechanism::RobotState *robot, const std::string &joint_name,
+bool JointPositionController::init(pr2_mechanism::RobotState *robot, const std::string &joint_name,
const control_toolbox::Pid &pid)
{
assert(robot);
@@ -72,7 +72,7 @@
return true;
}
-bool JointPositionController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool JointPositionController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
initialized_ = false;
assert(robot);
@@ -99,7 +99,7 @@
return init(robot, joint_name, pid);
}
-bool JointPositionController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool JointPositionController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
assert(robot);
node_ = n;
@@ -168,12 +168,12 @@
command_ = joint_state_->position_;
}
- if(joint_state_->joint_->type_ == mechanism::JOINT_ROTARY)
+ if(joint_state_->joint_->type_ == pr2_mechanism::JOINT_ROTARY)
{
angles::shortest_angular_distance_with_limits(command_, joint_state_->position_, joint_state_->joint_->joint_limit_min_, joint_state_->joint_->joint_limit_max_,error);
}
- else if(joint_state_->joint_->type_ == mechanism::JOINT_CONTINUOUS)
+ else if(joint_state_->joint_->type_ == pr2_mechanism::JOINT_CONTINUOUS)
{
error = angles::shortest_angular_distance(command_, joint_state_->position_);
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_ud_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_ud_calibration_controller.cpp 2009-09-01 00:23:22 UTC (rev 23436)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_ud_calibration_controller.cpp 2009-09-01 00:35:02 UTC (rev 23437)
@@ -52,7 +52,7 @@
{
}
-bool JointUDCalibrationController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool JointUDCalibrationController::initXml(pr2_mechanism::RobotState *robot, TiXmlElement *config)
{
assert(robot);
assert(config);
@@ -113,7 +113,7 @@
return true;
}
-bool JointUDCalibrationController::init(mechanism::RobotState *robot, const ros::NodeHandle &n)
+bool JointUDCalibrationController::init(pr2_mechanism::RobotState *robot, const ros::NodeHandle &n)
{
robot_ = robot;
node_ = n;
@@ -214,10 +214,10 @@
if (actuator_->state_.calibration_reading_)
{...
[truncated message content] |