|
From: <hsu...@us...> - 2008-09-08 21:46:47
|
Revision: 4048
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4048&view=rev
Author: hsujohnhsu
Date: 2008-09-08 21:46:56 +0000 (Mon, 08 Sep 2008)
Log Message:
-----------
controllers:
*joint_velocity_controllers: change joint_ to joint_state_ and robot_ to robot_state_
*add blank directory joint_controllers for upcoming migration from generic_controllers. also to move pid back to generic_controllers.
*updates to xml for new gripper.
Modified Paths:
--------------
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h
pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp
pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml
Added Paths:
-----------
pkg/trunk/controllers/joint_controllers/
pkg/trunk/controllers/joint_controllers/CMakeLists.txt
pkg/trunk/controllers/joint_controllers/Makefile
pkg/trunk/controllers/joint_controllers/include/
pkg/trunk/controllers/joint_controllers/include/joint_controllers/
pkg/trunk/controllers/joint_controllers/src/
pkg/trunk/controllers/joint_controllers/srv/
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-08 21:46:56 UTC (rev 4048)
@@ -87,8 +87,8 @@
* \param *joint The joint that is being controlled.
*/
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
+ void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot_state);
+ bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -126,7 +126,7 @@
private:
mechanism::JointState *joint_state_;
- mechanism::RobotState *robot_; /**< Pointer to robot structure. */
+ mechanism::RobotState *robot_state_; /**< Pointer to robot structure. */
Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
double command_; /**< Last commanded position. */
@@ -163,7 +163,7 @@
void update();
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
// Services
bool setCommand(generic_controllers::SetCommand::request &req,
Modified: pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp 2008-09-08 21:46:56 UTC (rev 4048)
@@ -41,7 +41,7 @@
ROS_REGISTER_CONTROLLER(JointVelocityController)
JointVelocityController::JointVelocityController()
-: joint_state_(NULL), robot_(NULL)
+: joint_state_(NULL), robot_state_(NULL)
{
// Initialize PID class
pid_controller_.initPid(0, 0, 0, 0, 0);
@@ -53,12 +53,39 @@
{
}
-bool JointVelocityController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+void JointVelocityController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot_state)
{
- assert(robot);
- robot_ = robot;
- last_time_ = robot->hw_->current_time_;
+ assert(robot_state);
+ robot_state_ = robot_state;
+ last_time_ = robot_state->hw_->current_time_;
+ // FIXME: BRING BACK THIS FUNCTION CALL...
+ // const char *joint_name = j->Attribute("name");
+ // joint_state_ = robot_state_->getJointState(joint_name);
+ // if (joint_state_ == NULL)
+ // {
+ // std::cout << "JointVelocityController could not find joint named: " << joint_name << std::endl;
+ // fprintf(stderr, "JointVelocityController could not find joint named \"%s\"\n", joint_name);
+ // return false;
+ // }
+ // std::cout << "JointVelocityController loaded joint named: " << joint_name << std::endl;
+
+ // TiXmlElement *p = j->FirstChildElement("pid");
+ // if (p)
+ // pid_controller_.initXml(p);
+ // else
+ // fprintf(stderr, "JointVelocityController's config did not specify the default pid parameters.\n");
+
+ // return true;
+
+}
+
+bool JointVelocityController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
+{
+ assert(robot_state);
+ robot_state_ = robot_state;
+ last_time_ = robot_state->hw_->current_time_;
+
TiXmlElement *j = config->FirstChildElement("joint");
if (!j)
{
@@ -67,13 +94,14 @@
}
const char *joint_name = j->Attribute("name");
- int index = joint_name ? robot->model_->getJointIndex(joint_name) : NULL;
- if (index < 0)
+ joint_state_ = robot_state_->getJointState(joint_name);
+ if (joint_state_ == NULL)
{
+ std::cout << "JointVelocityController could not find joint named: " << joint_name << std::endl;
fprintf(stderr, "JointVelocityController could not find joint named \"%s\"\n", joint_name);
return false;
}
- joint_state_ = &robot_->joint_states_[index];
+ std::cout << "JointVelocityController loaded joint named: " << joint_name << std::endl;
TiXmlElement *p = j->FirstChildElement("pid");
if (p)
@@ -98,7 +126,7 @@
double JointVelocityController::getTime()
{
- return robot_->hw_->current_time_;
+ return robot_state_->hw_->current_time_;
}
// Return the measured joint velocity
@@ -115,7 +143,7 @@
void JointVelocityController::update()
{
double error(0);
- double time = robot_->hw_->current_time_;
+ double time = robot_state_->hw_->current_time_;
error = joint_state_->velocity_ - command_;
joint_state_->commanded_effort_ = pid_controller_.updatePid(error, time - last_time_);
@@ -169,7 +197,7 @@
return true;
}
-bool JointVelocityControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool JointVelocityControllerNode::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
@@ -180,7 +208,7 @@
return false;
}
- if (!c_->initXml(robot, config))
+ if (!c_->initXml(robot_state, config))
return false;
node->advertise_service(topic + "/set_command", &JointVelocityControllerNode::setCommand, this);
node->advertise_service(topic + "/get_actual", &JointVelocityControllerNode::getActual, this);
Added: pkg/trunk/controllers/joint_controllers/CMakeLists.txt
===================================================================
--- pkg/trunk/controllers/joint_controllers/CMakeLists.txt (rev 0)
+++ pkg/trunk/controllers/joint_controllers/CMakeLists.txt 2008-09-08 21:46:56 UTC (rev 4048)
@@ -0,0 +1,6 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(joint_controllers)
+genmsg()
+gensrv()
+rospack_add_library(joint_controllers src/joint_effort_controller.cpp src/joint_position_controller.cpp src/joint_velocity_controller.cpp src/ramp_effort_controller.cpp src/sine_sweep_controller.cpp src/joint_pd_controller.cpp)
Added: pkg/trunk/controllers/joint_controllers/Makefile
===================================================================
--- pkg/trunk/controllers/joint_controllers/Makefile (rev 0)
+++ pkg/trunk/controllers/joint_controllers/Makefile 2008-09-08 21:46:56 UTC (rev 4048)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Modified: pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h 2008-09-08 21:46:56 UTC (rev 4048)
@@ -81,7 +81,7 @@
JointVelocityController controller_; /** controller for the link */
- mechanism::JointState *joint_; /** pointer to joint in Robot structure corresponding to link */
+ mechanism::JointState *joint_state_; /** pointer to joint in Robot structure corresponding to link */
BaseParam *parent_; /** pointer to parent corresponding to link */
@@ -203,7 +203,7 @@
/*!
* \brief Robot representation
*/
- mechanism::RobotState* robot_;
+ mechanism::RobotState* robot_state_;
/*!
Modified: pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp 2008-09-08 21:46:56 UTC (rev 4048)
@@ -268,6 +268,7 @@
{
c_->setJointPosCmd(req_goals_);
}
+
bool ArmPositionControllerNode::getJointPosCmd(pr2_controllers::GetJointPosCmd::request &req,
pr2_controllers::GetJointPosCmd::response &resp)
{
Modified: pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-08 21:46:56 UTC (rev 4048)
@@ -94,7 +94,7 @@
};
-void BaseController::init(std::vector<JointControlParam> jcp, mechanism::RobotState *robot)
+void BaseController::init(std::vector<JointControlParam> jcp, mechanism::RobotState *robot_state)
{
std::vector<JointControlParam>::iterator jcp_iter;
robot_desc::URDF::Link *link;
@@ -117,22 +117,27 @@
base_object.pos_.z = link->xyz[2];
base_object.name_ = joint_name;
base_object.parent_ = NULL;
- base_object.joint_ = robot->getJointState(joint_name);
+ base_object.joint_state_ = robot_state->getJointState(joint_name);
+ if (base_object.joint_state_==NULL)
+ std::cout << " unsuccessful getting joint state for " << joint_name << std::endl;
- abort();
- // TODO base_object.controller_.init(jcp_iter->p_gain,jcp_iter->i_gain,jcp_iter->d_gain,jcp_iter->windup,0.0,jcp_iter->joint_name,robot);
+ //abort();
+ base_object.controller_.init(jcp_iter->p_gain,jcp_iter->i_gain,jcp_iter->d_gain,jcp_iter->windup,0.0,jcp_iter->joint_name,robot_state);
if(joint_name.find("caster") != string::npos)
{
+ std::cout << " assigning casters " << joint_name << std::endl;
base_object.local_id_ = num_casters_;
base_casters_.push_back(base_object);
steer_angle_actual_.push_back(0);
steer_velocity_desired_.push_back(0);
num_casters_++;
-// cout << "base_casters" << ":: " << base_object;
+ cout << "base_casters" << ":: " << base_object;
}
+
if(joint_name.find("wheel") != string::npos)
{
+ std::cout << " assigning wheels " << joint_name << std::endl;
base_object.local_id_ = num_wheels_;
if(joint_name.find("_r_") != string::npos)
base_object.direction_multiplier_ = 1;
@@ -173,12 +178,12 @@
{
wheel_radius_ = DEFAULT_WHEEL_RADIUS;
}
- robot_ = robot;
+ robot_state_ = robot_state;
- last_time_ = robot_->hw_->current_time_;
+ last_time_ = robot_state_->hw_->current_time_;
}
-bool BaseController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool BaseController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
std::cout << " base controller name: " << config->Attribute("name") << std::endl;
TiXmlElement *elt = config->FirstChildElement("controller");
@@ -227,14 +232,14 @@
// std::cout << " sub map : " << elt->Attribute("name") << std::endl;
elt = config->NextSiblingElement("map");
}
- init(jcp_vec,robot);
+ init(jcp_vec,robot_state);
return true;
}
void BaseController::getJointValues()
{
for(int i=0; i < num_casters_; i++)
- steer_angle_actual_[i] = base_casters_[i].joint_->position_;
+ steer_angle_actual_[i] = base_casters_[i].joint_state_->position_;
for(int i=0; i < num_wheels_; i++)
wheel_speed_actual_[i] = base_wheels_[i].controller_.getMeasuredVelocity();
@@ -251,7 +256,7 @@
double steer_angle;
for(int i=0; i < num_wheels_; i++)
{
- steer_angle = base_wheels_[i].parent_->joint_->position_;
+ steer_angle = base_wheels_[i].parent_->joint_state_->position_;
// res1 = rotate2D(base_wheels_[i].pos_,steer_angle);
// cout << "init position" << base_wheels_[i].pos_.x << " " << base_wheels_[i].pos_.y << " " << base_wheels_[i].pos_.z << endl;
res1 = base_wheels_[i].pos_.rot2D(steer_angle);
@@ -266,7 +271,7 @@
void BaseController::update()
{
- double current_time = robot_->hw_->current_time_;
+ double current_time = robot_state_->hw_->current_time_;
if(pthread_mutex_trylock(&base_controller_lock_)==0)
{
@@ -287,7 +292,7 @@
computeOdometry(current_time);
- if(odom_publish_counter_ > odom_publish_count_)
+ if(odom_publish_counter_ > odom_publish_count_) // FIXME: time based rate limiting
{
(ros::g_node)->publish("odom", odom_msg_);
odom_publish_counter_ = 0;
@@ -335,7 +340,7 @@
{
caster_2d_velocity.z = steer_velocity_desired_[base_wheels_[i].parent_->local_id_];
- steer_angle_actual = base_wheels_[i].parent_->joint_->position_;
+ steer_angle_actual = base_wheels_[i].parent_->joint_state_->position_;
wheel_point_velocity = computePointVelocity2D(base_wheels_position_[i],cmd_vel_);
// cout << "wheel_point_velocity" << wheel_point_velocity << ",pos::" << base_wheels_position_[i] << ",cmd::" << cmd_vel_ << endl;
@@ -416,12 +421,12 @@
return true;
}
-bool BaseControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool BaseControllerNode::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
string prefix = config->Attribute("name");
- if(!c_->initXml(robot, config))
+ if(!c_->initXml(robot_state, config))
return false;
node->advertise_service(prefix + "/set_command", &BaseControllerNode::setCommand, this);
@@ -485,8 +490,8 @@
base_odom_position_ += base_odom_delta;
odom_msg_.header.frame_id = "FRAMEID_ODOM";
- odom_msg_.header.stamp.sec = (unsigned long)floor(robot_->hw_->current_time_);
- odom_msg_.header.stamp.nsec = (unsigned long)floor( 1e9 * ( robot_->hw_->current_time_ - odom_msg_.header.stamp.sec) );
+ odom_msg_.header.stamp.sec = (unsigned long)floor(robot_state_->hw_->current_time_);
+ odom_msg_.header.stamp.nsec = (unsigned long)floor( 1e9 * ( robot_state_->hw_->current_time_ - odom_msg_.header.stamp.sec) );
odom_msg_.pos.x = base_odom_position_.x;
odom_msg_.pos.y = base_odom_position_.y;
@@ -508,7 +513,7 @@
double steer_angle;
for(int i = 0; i < num_wheels_; i++) {
- steer_angle = base_wheels_[i].parent_->joint_->position_;
+ steer_angle = base_wheels_[i].parent_->joint_state_->position_;
A.element(i*2,0) = cos(steer_angle)*wheel_radius_*(wheel_speed_actual_[i]);
A.element(i*2+1,0) = sin(steer_angle)*wheel_radius_*(wheel_speed_actual_[i]);
// if(isnan(steer_angle))
@@ -566,7 +571,7 @@
std::ostream & controller::operator<<(std::ostream& mystream, const controller::BaseParam &bp)
{
- mystream << "BaseParam" << bp.name_ << endl << "position " << bp.pos_ << "id " << bp.local_id_ << endl << "joint " << bp.joint_->joint_->name_ << endl << endl;
+ mystream << "BaseParam" << bp.name_ << endl << "position " << bp.pos_ << "id " << bp.local_id_ << endl << "joint " << bp.joint_state_->joint_->name_ << endl << endl;
return mystream;
};
@@ -651,30 +656,30 @@
// Matrix D(3,1);
// for(int i = 0; i < NUM_CASTERS; i++) {
-// A.element(i*4,0) = cos(robot->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot->joint[i*3+1].velocity;
-// A.element(i*4+1,0) = sin(robot->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot->joint[i*3+1].velocity;
-// A.element(i*4+2,0) = cos(robot->joint[i*3].position) *WHEEL_RADIUS*robot->joint[i*3+2].velocity;
-// A.element(i*4+3,0) = sin(robot->joint[i*3].position)* WHEEL_RADIUS*robot->joint[i*3+2].velocity;
+// A.element(i*4,0) = cos(robot_state->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot_state->joint[i*3+1].velocity;
+// A.element(i*4+1,0) = sin(robot_state->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot_state->joint[i*3+1].velocity;
+// A.element(i*4+2,0) = cos(robot_state->joint[i*3].position) *WHEEL_RADIUS*robot_state->joint[i*3+2].velocity;
+// A.element(i*4+3,0) = sin(robot_state->joint[i*3].position)* WHEEL_RADIUS*robot_state->joint[i*3+2].velocity;
// }
// /*
// for(int i = 0; i < (NUM_WHEELS + NUM_CASTERS); i++) {
-// printf("i: %i pos : %03f vel: %03f\n", i,robot->joint[i].position, robot->joint[i].velocity);
+// printf("i: %i pos : %03f vel: %03f\n", i,robot_state->joint[i].position, robot_state->joint[i].velocity);
// }
// */
// for(int i = 0; i < NUM_CASTERS; i++) {
// C.element(i*4, 0) = 1;
// C.element(i*4, 1) = 0;
-// C.element(i*4, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
+// C.element(i*4, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot_state->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
// C.element(i*4+1, 0) = 0;
// C.element(i*4+1, 1) = 1;
-// C.element(i*4+1, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
+// C.element(i*4+1, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot_state->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
// C.element(i*4+2, 0) = 1;
// C.element(i*4+2, 1) = 0;
-// C.element(i*4+2, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
+// C.element(i*4+2, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot_state->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
// C.element(i*4+3, 0) = 0;
// C.element(i*4+3, 1) = 1;
-// C.element(i*4+3, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
+// C.element(i*4+3, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot_state->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
// }
// D = pseudoInverse(C)*A;
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml 2008-09-08 21:46:56 UTC (rev 4048)
@@ -123,7 +123,7 @@
</controller>
<!-- Special gripper joint -->
<controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
- <joint name="gripper_left_joint">
+ <joint name="finger_l_left_joint">
<pid p="10" d="0" i="0" iClamp="0" />
<gripper_defaults effortLimit="100" velocityLimit="10" />
</joint>
@@ -175,7 +175,7 @@
</controller>
<!-- Special gripper joint -->
<controller name="gripper_right_controller" topic="gripper_right_controller" type="JointPositionControllerNode">
- <joint name="gripper_right_joint">
+ <joint name="finger_l_right_joint">
<pid p="10" d="0" i="0" iClamp="0" />
<gripper_defaults effortLimit="100" velocityLimit="10" />
</joint>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml 2008-09-08 21:46:56 UTC (rev 4048)
@@ -81,7 +81,7 @@
<explicitDampingCoefficient>1.0</explicitDampingCoefficient>
</joint>
<!-- Special gripper joint -->
- <joint name="gripper_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <joint name="finger_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
<left_proximal>finger_l_left_joint</left_proximal>
@@ -120,7 +120,7 @@
<explicitDampingCoefficient>1.0</explicitDampingCoefficient>
</joint>
<!-- Special gripper joint -->
- <joint name="gripper_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <joint name="finger_l_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
<left_proximal>finger_l_right_joint</left_proximal>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|