|
From: <hsu...@us...> - 2008-07-03 00:43:06
|
Revision: 1234
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=1234&view=rev
Author: hsujohnhsu
Date: 2008-07-02 17:43:14 -0700 (Wed, 02 Jul 2008)
Log Message:
-----------
fix indents for pr2.xml and base_node.cpp.
increase saturationTorques for spine elevator slider in sim.
Modified Paths:
--------------
pkg/trunk/demos/2dnav-gazebo/world/robot.world
pkg/trunk/demos/2dnav-gazebo/world/robot_test.world
pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world
pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp
pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml
Modified: pkg/trunk/demos/2dnav-gazebo/world/robot.world
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/world/robot.world 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/demos/2dnav-gazebo/world/robot.world 2008-07-03 00:43:14 UTC (rev 1234)
@@ -505,7 +505,7 @@
</joint>
<!-- ========================================= -->
<joint name="torso_spine_slider">
- <saturationTorque>100</saturationTorque>
+ <saturationTorque>1000</saturationTorque>
<pGain>1</pGain>
<dGain>0</dGain>
<iGain>0</iGain>
Modified: pkg/trunk/demos/2dnav-gazebo/world/robot_test.world
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/world/robot_test.world 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/demos/2dnav-gazebo/world/robot_test.world 2008-07-03 00:43:14 UTC (rev 1234)
@@ -505,7 +505,7 @@
</joint>
<!-- ========================================= -->
<joint name="torso_spine_slider">
- <saturationTorque>100</saturationTorque>
+ <saturationTorque>1000</saturationTorque>
<pGain>100</pGain>
<dGain>0</dGain>
<iGain>0</iGain>
Modified: pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/demos/2dnav-gazebo/world/robot_torque.world 2008-07-03 00:43:14 UTC (rev 1234)
@@ -505,8 +505,8 @@
</joint>
<!-- ========================================= -->
<joint name="torso_spine_slider">
- <saturationTorque>100</saturationTorque>
- <pGain>100</pGain>
+ <saturationTorque>1000</saturationTorque>
+ <pGain>1</pGain>
<dGain>0</dGain>
<iGain>0</iGain>
<iClamp>0</iClamp>
Modified: pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp
===================================================================
--- pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/drivers/motor/etherdrive/src/base_node/base_node.cpp 2008-07-03 00:43:14 UTC (rev 1234)
@@ -35,215 +35,231 @@
class EtherDrive_Node : public ros::node
{
-public:
- std_msgs::ActuatorState mot[12];
- std_msgs::ActuatorCmd mot_cmd[12];
+ public:
+ std_msgs::ActuatorState mot[12];
+ std_msgs::ActuatorCmd mot_cmd[12];
- string host;
- string host2;
- EtherDrive *edRight;
- EtherDrive *edLeft;
- int frame_id;
+ string host;
+ string host2;
+ EtherDrive *edRight;
+ EtherDrive *edLeft;
+ int frame_id;
- float last_mot_val[12];
- double pulse_per_rad[12];
+ float last_mot_val[12];
+ double pulse_per_rad[12];
- int lastEncPos[12];
- int mode; // 0=voltage, 1=current, 2=position, 3=velocity, 4=position on comp
- bool firstTimeVelCtrl;
- int fooCounter;
- int counter;
- float last_mot_cmd[12];
+ int lastEncPos[12];
+ int mode; // 0=voltage, 1=current, 2=position, 3=velocity, 4=position on comp
+ bool firstTimeVelCtrl;
+ int fooCounter;
+ int counter;
+ float last_mot_cmd[12];
- EtherDrive_Node() : ros::node("etherdrive"), edLeft(NULL)
- {
- for (int i = 0;i < 12;i++) {
- ostringstream oss;
- oss << "mot" << i;
- advertise<std_msgs::ActuatorState>(oss.str().c_str());
+ EtherDrive_Node() : ros::node("etherdrive"), edLeft(NULL)
+ {
+ for (int i = 0;i < 12;i++)
+ {
+ ostringstream oss;
+ oss << "mot" << i;
+ advertise<std_msgs::ActuatorState>(oss.str().c_str());
- oss << "_cmd";
- subscribe(oss.str().c_str(), mot_cmd[i], &EtherDrive_Node::mot_callback);
- last_mot_val[i] = 0;
- }
+ oss << "_cmd";
+ subscribe(oss.str().c_str(), mot_cmd[i], &EtherDrive_Node::mot_callback);
+ last_mot_val[i] = 0;
+ }
- //if (!get_param(string(".host"), host))
- // host = "192.168.1.12";
-// host[0] = "10.12.0.103";
- host = "10.11.0.102";
- host2 = "10.12.0.103";
- printf("EtherDrive host set to [%s]\n",host.c_str());
+ //if (!get_param(string(".host"), host))
+ // host = "192.168.1.12";
+ // host[0] = "10.12.0.103";
+ host = "10.11.0.102";
+ host2 = "10.12.0.103";
+ printf("EtherDrive host set to [%s]\n",host.c_str());
- //if (!get_param(string(".frame_id"), frame_id))
- frame_id = -1;
- printf("EtherDrive frame_id set to [%d]\n", frame_id);
+ //if (!get_param(string(".frame_id"), frame_id))
+ frame_id = -1;
+ printf("EtherDrive frame_id set to [%d]\n", frame_id);
- for (int i = 0;i < 12;i++) {
- ostringstream oss;
- oss << "pulse_per_rad" << i;
- //if (!get_param(oss.str().c_str(), pulse_per_rad[i]))
- pulse_per_rad[i] = 1591.54943;
- printf("Using %g pulse_per_rad for motor %d\n", pulse_per_rad[i], i);
- }
+ for (int i = 0;i < 12;i++)
+ {
+ ostringstream oss;
+ oss << "pulse_per_rad" << i;
+ //if (!get_param(oss.str().c_str(), pulse_per_rad[i]))
+ pulse_per_rad[i] = 1591.54943;
+ printf("Using %g pulse_per_rad for motor %d\n", pulse_per_rad[i], i);
+ }
- edLeft = new EtherDrive();
- edLeft->init(host, "10.11.0.3");
- edRight = new EtherDrive();
- edRight->init(host2, "10.12.0.2");
+ edLeft = new EtherDrive();
+ edLeft->init(host, "10.11.0.3");
+ edRight = new EtherDrive();
+ edRight->init(host2, "10.12.0.2");
- // debugging JS: initialize values
- for (int i = 0; i < 12; i++) {
- mot_cmd[i].valid = true;
- mot_cmd[i].rel = 0;
- mot_cmd[i].cmd = 0;
- }
- // debugging JS: initialize values
- for (int i = 0; i < 6; i++) {
- // setting gains on controls on ethercard drive
- edLeft->set_gain(i,'P',0);
- edLeft->set_gain(i,'I',10);
- edLeft->set_gain(i,'D',0);
- edLeft->set_gain(i,'W',100);
- edLeft->set_gain(i,'M',1004);
- edLeft->set_gain(i,'Z',1);
- edRight->set_gain(i,'P',0);
- edRight->set_gain(i,'I',10);
- edRight->set_gain(i,'D',0);
- edRight->set_gain(i,'W',100);
- edRight->set_gain(i,'M',1004);
- edRight->set_gain(i,'Z',1);
- }
-
-
- edLeft->set_control_mode(1); // 0=voltage, 1=current control
- edRight->set_control_mode(1); // 0=voltage, 1=current control
+ // debugging JS: initialize values
+ for (int i = 0; i < 12; i++)
+ {
+ mot_cmd[i].valid = true;
+ mot_cmd[i].rel = 0;
+ mot_cmd[i].cmd = 0;
+ }
+ // debugging JS: initialize values
+ for (int i = 0; i < 6; i++)
+ {
+ // setting gains on controls on ethercard drive
+ edLeft->set_gain(i,'P',0);
+ edLeft->set_gain(i,'I',10);
+ edLeft->set_gain(i,'D',0);
+ edLeft->set_gain(i,'W',100);
+ edLeft->set_gain(i,'M',1004);
+ edLeft->set_gain(i,'Z',1);
+ edRight->set_gain(i,'P',0);
+ edRight->set_gain(i,'I',10);
+ edRight->set_gain(i,'D',0);
+ edRight->set_gain(i,'W',100);
+ edRight->set_gain(i,'M',1004);
+ edRight->set_gain(i,'Z',1);
+ }
+
+
+ edLeft->set_control_mode(1); // 0=voltage, 1=current control
+ edRight->set_control_mode(1); // 0=voltage, 1=current control
- firstTimeVelCtrl = true;
- fooCounter = 0;
- edLeft->motors_on();
- edRight->motors_on();
+ firstTimeVelCtrl = true;
+ fooCounter = 0;
+ edLeft->motors_on();
+ edRight->motors_on();
- counter = 0;
- }
+ counter = 0;
+ }
- void mot_callback() {
- //printf("received motor 3 command %f\n", mot_cmd[3].val);
- }
+ void mot_callback()
+ {
+ //printf("received motor 3 command %f\n", mot_cmd[3].val);
+ }
- virtual ~EtherDrive_Node()
- {
- if (edRight) {
- printf("deleting edRight\n");
- delete edRight;
- }
- if (edLeft) {
- printf("deleting edLeft\n");
- delete edLeft;
+ virtual ~EtherDrive_Node()
+ {
+ if (edRight)
+ {
+ printf("deleting edRight\n");
+ delete edRight;
+ }
+ if (edLeft)
+ {
+ printf("deleting edLeft\n");
+ delete edLeft;
+ }
+ int footmp[6] = {0,0,0,0,0,0};
+ edLeft->drive(6,footmp);
+ edRight->drive(6,footmp);
}
- int footmp[6] = {0,0,0,0,0,0};
- edLeft->drive(6,footmp);
- edRight->drive(6,footmp);
- }
- bool do_tick()
- {
+ bool do_tick()
+ {
- int tmp_mot_cmd[12];
- int tmp_mot_cmd_left[6];
- int tmp_mot_cmd_right[6];
- int currEncPos[12];
+ int tmp_mot_cmd[12];
+ int tmp_mot_cmd_left[6];
+ int tmp_mot_cmd_right[6];
+ int currEncPos[12];
- float curVel;
- float desVel;
- float desPos[12];
-// float k_p[12] = {5,5,-1,5,5,-1, 5,5,-1,5,5,-1};
- float k_p[12] = {5,5,-0.5,5,5,-0.5, 5,5,-0.5,5,5,-0.5};
-// float k_p[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
- float k_i[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
- float k_d[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
-// float k_i[12] = {0,0,-0.01,0,0,-0.01, 0,0,-0.01,0,0,0};
-// float k_d[12] = {0,0,-0.08,0,0,-0.08, 0,0,-0.08,0,0,-0.08};
- float k_cross[12] = {-1, -1, 0 , -1, -1, 0, -1, -1, 0 , -1, -1, 0};
- float foo;
+ float curVel;
+ float desVel;
+ float desPos[12];
+ // float k_p[12] = {5,5,-1,5,5,-1, 5,5,-1,5,5,-1};
+ float k_p[12] = {5,5,-0.5,5,5,-0.5, 5,5,-0.5,5,5,-0.5};
+ // float k_p[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
+ float k_i[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
+ float k_d[12] = {0,0,0,0,0,0,0,0,0,0,0,0};
+ // float k_i[12] = {0,0,-0.01,0,0,-0.01, 0,0,-0.01,0,0,0};
+ // float k_d[12] = {0,0,-0.08,0,0,-0.08, 0,0,-0.08,0,0,-0.08};
+ float k_cross[12] = {-1, -1, 0 , -1, -1, 0, -1, -1, 0 , -1, -1, 0};
+ float foo;
- float posError[12];
- float intPosError[12];
- float lastPosError[12];
+ float posError[12];
+ float intPosError[12];
+ float lastPosError[12];
- for (int i = 0; i < 12; i++) {
- mot_cmd[i].lock();
- if(i == 2|i == 5|i == 8|i == 11) { // turret motors, position control
- desPos[i] = float(mot_cmd[i].cmd)/360*90000;
- if(i < 6) posError[i] = desPos[i] - float(edLeft->get_enc(i));
- else posError[i] = desPos[i] - float(edRight->get_enc(i-6));
-if(i==11) printf("posError: %f, despos: %f, enc: %i\n", posError[i], desPos[i], edRight->get_enc(i-6));
+ for (int i = 0; i < 12; i++)
+ {
+ mot_cmd[i].lock();
+ if(i == 2|i == 5|i == 8|i == 11)
+ { // turret motors, position control
+ desPos[i] = float(mot_cmd[i].cmd)/360*90000;
+ if(i < 6) posError[i] = desPos[i] - float(edLeft->get_enc(i));
+ else posError[i] = desPos[i] - float(edRight->get_enc(i-6));
+ if(i==11) printf("posError: %f, despos: %f, enc: %i\n", posError[i], desPos[i], edRight->get_enc(i-6));
- tmp_mot_cmd[i] = int(k_p[i]*posError[i]) + int(k_d[i]*(posError[i]-lastPosError[i])/0.001) + int(k_i[i]*intPosError[i]);
+ tmp_mot_cmd[i] = int(k_p[i]*posError[i]) + int(k_d[i]*(posError[i]-lastPosError[i])/0.001) + int(k_i[i]*intPosError[i]);
- lastPosError[i] = posError[i];
- intPosError[i] += posError[i];
- }
- else { // wheels, velocity control
+ lastPosError[i] = posError[i];
+ intPosError[i] += posError[i];
+ }
+ else
+ { // wheels, velocity control
+
+ if(i<6) currEncPos[i] = edLeft->get_enc(i);
+ else currEncPos[i] = edRight->get_enc(i-6);
+ curVel = float(currEncPos[i] - lastEncPos[i])/9000*0.48;
+ desVel = mot_cmd[i].cmd; // enc units/msec. should be (wheel rev/s)
+ if(i == 0| i ==1) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[2]);
+ else if(i == 3| i ==4) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[5]);
+ else if(i == 6| i ==7) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[8]);
+ else if(i == 9| i ==10) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[11]);
+ lastEncPos[i] = currEncPos[i];
+ }
+
+ mot_cmd[i].valid = false; // set to invalid so we don't re-use
+ mot_cmd[i].unlock();
+ if(tmp_mot_cmd[i] > 3000)
+ {
+ tmp_mot_cmd[i] = 3000;
+ // printf("Max +ve current motor %i\n", i);
+ }
+ if(tmp_mot_cmd[i] < -3000)
+ {
+ tmp_mot_cmd[i] = -3000;
+ // printf("Max -ve current motor %i \n", i);
+ }
- if(i<6) currEncPos[i] = edLeft->get_enc(i);
- else currEncPos[i] = edRight->get_enc(i-6);
- curVel = float(currEncPos[i] - lastEncPos[i])/9000*0.48;
- desVel = mot_cmd[i].cmd; // enc units/msec. should be (wheel rev/s)
- if(i == 0| i ==1) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[2]);
- else if(i == 3| i ==4) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[5]);
- else if(i == 6| i ==7) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[8]);
- else if(i == 9| i ==10) tmp_mot_cmd[i] = int(k_p[i]*(desVel - curVel) + k_cross[i]*tmp_mot_cmd[11]);
- lastEncPos[i] = currEncPos[i];
}
- mot_cmd[i].valid = false; // set to invalid so we don't re-use
- mot_cmd[i].unlock();
- if(tmp_mot_cmd[i] > 3000) {
- tmp_mot_cmd[i] = 3000;
- // printf("Max +ve current motor %i\n", i);
+ // edLeft->drive(6,tmp_mot_cmd);
+ for(int i = 0; i<6; i++)
+ {
+ tmp_mot_cmd_left[i] = tmp_mot_cmd[i];
+ tmp_mot_cmd_right[i] = tmp_mot_cmd[i+6];
+ }
+ edLeft->drive(6,tmp_mot_cmd_left);
+ edRight->drive(6,tmp_mot_cmd_right);
+ // int footmp[6] = {500,500,0,500,500,0};
+ // edRight->drive(6,footmp);
+ // edLeft->drive(6,footmp);
+
+ int valLeft[6];
+ int valRight[6];
+ if (!edLeft->tick(6,valLeft))
+ {
+ return false;
}
- if(tmp_mot_cmd[i] < -3000) {
- tmp_mot_cmd[i] = -3000;
- // printf("Max -ve current motor %i \n", i);
+ if (!edRight->tick(6,valRight))
+ {
+ return false;
}
-
- }
-// edLeft->drive(6,tmp_mot_cmd);
- for(int i = 0; i<6; i++) {
- tmp_mot_cmd_left[i] = tmp_mot_cmd[i];
- tmp_mot_cmd_right[i] = tmp_mot_cmd[i+6];
- }
- edLeft->drive(6,tmp_mot_cmd_left);
- edRight->drive(6,tmp_mot_cmd_right);
-// int footmp[6] = {500,500,0,500,500,0};
-// edRight->drive(6,footmp);
-// edLeft->drive(6,footmp);
+
+ for (int i = 0; i < 6; i++)
+ {
+ mot[i].pos_valid = true;
+ mot[i].pos = edLeft->get_enc(i);
+ mot[i+6].pos = edRight->get_enc(i);
+ ostringstream oss;
+ oss << "mot" << i;
+ publish(oss.str().c_str(), mot[i]);
+ }
+ return true;
+ } // end do_tick()
- int valLeft[6];
- int valRight[6];
- if (!edLeft->tick(6,valLeft)) {
- return false;
- }
- if (!edRight->tick(6,valRight)) {
- return false;
- }
-
-
- for (int i = 0; i < 6; i++) {
- mot[i].pos_valid = true;
- mot[i].pos = edLeft->get_enc(i);
- mot[i+6].pos = edRight->get_enc(i);
- ostringstream oss;
- oss << "mot" << i;
- publish(oss.str().c_str(), mot[i]);
- }
- return true;
- } // end do_tick()
-
};
int main(int argc, char **argv)
@@ -251,7 +267,8 @@
ros::init(argc, argv);
EtherDrive_Node a;
printf("start\n");
- while (a.ok()) {
+ while (a.ok())
+ {
usleep(1000);
if (!a.do_tick())
{
Modified: pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml 2008-07-03 00:28:38 UTC (rev 1233)
+++ pkg/trunk/drivers/robot/pr2/pr2Core/include/pr2Core/pr2.xml 2008-07-03 00:43:14 UTC (rev 1234)
@@ -6,475 +6,472 @@
<!-- Begin constant dimensions -->
- <constants>
+ <constants>
- <wheel_length>0.03</wheel_length>
- <wheel_radius>0.08</wheel_radius>
+ <wheel_length>0.03</wheel_length>
+ <wheel_radius>0.08</wheel_radius>
- <shoulder_pan_length>0.4</shoulder_pan_length>
- <shoulder_pan_radius>0.05</shoulder_pan_radius>
+ <shoulder_pan_length>0.4</shoulder_pan_length>
+ <shoulder_pan_radius>0.05</shoulder_pan_radius>
- <shoulder_pitch_length>0.01</shoulder_pitch_length>
- <shoulder_pitch_radius>0.01</shoulder_pitch_radius>
+ <shoulder_pitch_length>0.01</shoulder_pitch_length>
+ <shoulder_pitch_radius>0.01</shoulder_pitch_radius>
- <shoulder_roll_length>0.4</shoulder_roll_length>
- <shoulder_roll_radius>0.05</shoulder_roll_radius>
+ <shoulder_roll_length>0.4</shoulder_roll_length>
+ <shoulder_roll_radius>0.05</shoulder_roll_radius>
- <elbow_pitch_length>0.09085</elbow_pitch_length>
- <elbow_pitch_radius>0.05</elbow_pitch_radius>
+ <elbow_pitch_length>0.09085</elbow_pitch_length>
+ <elbow_pitch_radius>0.05</elbow_pitch_radius>
- <forearm_roll_length>0.2237</forearm_roll_length>
- <forearm_roll_radius>0.05</forearm_roll_radius>
+ <forearm_roll_length>0.2237</forearm_roll_length>
+ <forearm_roll_radius>0.05</forearm_roll_radius>
- <wrist_pitch_length>0.01</wrist_pitch_length>
- <wrist_pitch_radius>0.01</wrist_pitch_radius>
+ <wrist_pitch_length>0.01</wrist_pitch_length>
+ <wrist_pitch_radius>0.01</wrist_pitch_radius>
- <wrist_roll_length>0.01</wrist_roll_length>
- <wrist_roll_radius>0.01</wrist_roll_radius>
+ <wrist_roll_length>0.01</wrist_roll_length>
+ <wrist_roll_radius>0.01</wrist_roll_radius>
- <base_length>0.5</base_length>
- <base_width>0.5</base_width>
- <base_height>0.1</base_height>
+ <base_length>0.5</base_length>
+ <base_width>0.5</base_width>
+ <base_height>0.1</base_height>
- <torso_length>0.3</torso_length>
- <torso_width>0.05</torso_width>
- <torso_height>0.8</torso_height>
+ <torso_length>0.3</torso_length>
+ <torso_width>0.05</torso_width>
+ <torso_height>0.8</torso_height>
- <head_pan_length>0.1</head_pan_length>
- <head_pan_radius>0.5</head_pan_radius>
+ <head_pan_length>0.1</head_pan_length>
+ <head_pan_radius>0.5</head_pan_radius>
- <head_tilt_length>0.25</head_tilt_length>
- <head_tilt_width>0.1</head_tilt_width>
- <head_tilt_height>0.15</head_tilt_height>
+ <head_tilt_length>0.25</head_tilt_length>
+ <head_tilt_width>0.1</head_tilt_width>
+ <head_tilt_height>0.15</head_tilt_height>
- </constants>
+ </constants>
<!-- End constant dimensions -->
- <templates>
- <define template="pr2_caster_visual">
- <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
- <size>0 0</size>
- </geometry>
- </define>
+ <templates>
+ <define template="pr2_caster_visual">
+ <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
+ <size>0 0</size>
+ </geometry>
+ </define>
- <define template="pr2_caster_inertial">
- <mass> 3.473082 </mass>
- <com> 0.007342 0.00015 0.095236 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
- </define>
+ <define template="pr2_caster_inertial">
+ <mass> 3.473082 </mass>
+ <com> 0.007342 0.00015 0.095236 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
+ </define>
- <define template="pr2_caster_joint" type="revolute">
- <axis> 0 0 1 </axis> <!-- direction of the joint in the local coordinate frame -->
- <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_caster_joint" type="revolute">
+ <axis> 0 0 1 </axis> <!-- direction of the joint in the local coordinate frame -->
+ <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_wheel_visual">
- <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
- <size>wheel_length wheel_radius</size>
- </geometry>
- </define>
+ <define template="pr2_wheel_visual">
+ <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder"><!-- geometry specified using a simple geometric object -->
+ <size>wheel_length wheel_radius</size>
+ </geometry>
+ </define>
- <define template="pr2_wheel_inertial">
- <mass> 0.44036 </mass>
- <com> 0.000008 0.000008 0.008475 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
- </define>
+ <define template="pr2_wheel_inertial">
+ <mass> 0.44036 </mass>
+ <com> 0.000008 0.000008 0.008475 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012411765597 -0.000711733678 0.00050272983 0.015218160428 -0.000004273467 0.011763977943 </inertia>
+ </define>
- <define template="pr2_wheel_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in the local coordinate frame -->
- <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_wheel_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in the local coordinate frame -->
+ <anchor>0 0 0</anchor> <!-- point on the joint relative to the local coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_pan_joint" type="revolute">
- <axis> 0 0 1 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -M_PI/2 M_PI/2 </limit>
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_shoulder_pan_joint" type="revolute">
+ <axis> 0 0 1 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -M_PI/2 M_PI/2 </limit>
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_pan_inertial">
- <mass> 16.29553 </mass>
- <com> -0.005215 -0.030552 -0.175743 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia>0.793291393007 0.003412032973 0.0096614481 0.818419457224 -0.033999499551 0.13915007406 </inertia>
- </define>
+ <define template="pr2_shoulder_pan_inertial">
+ <mass> 16.29553 </mass>
+ <com> -0.005215 -0.030552 -0.175743 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia>0.793291393007 0.003412032973 0.0096614481 0.818419457224 -0.033999499551 0.13915007406 </inertia>
+ </define>
- <define template="pr2_shoulder_pan_visual">
- <xyz>0 0 -shoulder_pan_length/2 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0 0 0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size> shoulder_pan_length shoulder_pan_radius </size>
- </geometry>
- </define>
+ <define template="pr2_shoulder_pan_visual">
+ <xyz>0 0 -shoulder_pan_length/2 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0 0 0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size> shoulder_pan_length shoulder_pan_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_shoulder_pitch_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -0.6109 1.3090 </limit>
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_shoulder_pitch_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -0.6109 1.3090 </limit>
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_pitch_inertial">
- <mass> 2.41223 </mass>
- <com> -0.035895 0.014422 -0.028263</com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.016640333585 0.002696462583 0.001337742275 0.017232603914 -0.003605106514 0.018723553425</inertia>
- </define>
+ <define template="pr2_shoulder_pitch_inertial">
+ <mass> 2.41223 </mass>
+ <com> -0.035895 0.014422 -0.028263</com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.016640333585 0.002696462583 0.001337742275 0.017232603914 -0.003605106514 0.018723553425</inertia>
+ </define>
- <define template="pr2_shoulder_pitch_visual">
- <xyz>shoulder_pitch_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>M_PI/2 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size> shoulder_pitch_length shoulder_pitch_radius </size>
- </geometry>
- </define>
+ <define template="pr2_shoulder_pitch_visual">
+ <xyz>shoulder_pitch_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>M_PI/2 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size> shoulder_pitch_length shoulder_pitch_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_shoulder_roll_joint" type="revolute">
- <axis> 1 0 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -2.3562 2.3562 </limit>
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_shoulder_roll_joint" type="revolute">
+ <axis> 1 0 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -2.3562 2.3562 </limit>
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_shoulder_roll_inertial">
- <mass> 4.9481 </mass>
- <com> 0.001205 -0.016293 0.21227 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.073060715309 0.000547745916 0.000119476885 0.072124510748 0.001544932307 0.013383284908</inertia>
- </define>
+ <define template="pr2_shoulder_roll_inertial">
+ <mass> 4.9481 </mass>
+ <com> 0.001205 -0.016293 0.21227 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.073060715309 0.000547745916 0.000119476885 0.072124510748 0.001544932307 0.013383284908</inertia>
+ </define>
- <define template="pr2_shoulder_roll_visual">
- <xyz>shoulder_roll_length/2 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size> shoulder_roll_length shoulder_roll_radius </size>
- </geometry>
- </define>
+ <define template="pr2_shoulder_roll_visual">
+ <xyz>shoulder_roll_length/2 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size> shoulder_roll_length shoulder_roll_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_elbow_pitch_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -M_PI/2 0.8727 </limit>
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_elbow_pitch_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -M_PI/2 0.8727 </limit>
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_elbow_pitch_inertial">
- <mass> 1.689246 </mass>
- <com> -0.011638 0.013173 0.001228 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.003275298548 0.000292046674 -0.000077359282 0.003236815206 -0.000001162155 0.00410053774 </inertia>
- </define>
+ <define template="pr2_elbow_pitch_inertial">
+ <mass> 1.689246 </mass>
+ <com> -0.011638 0.013173 0.001228 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.003275298548 0.000292046674 -0.000077359282 0.003236815206 -0.000001162155 0.00410053774 </inertia>
+ </define>
- <define template="pr2_elbow_pitch_visual">
- <xyz>elbow_pitch_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size>elbow_pitch_length elbow_pitch_radius </size>
- </geometry>
- </define>
+ <define template="pr2_elbow_pitch_visual">
+ <xyz>elbow_pitch_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size>elbow_pitch_length elbow_pitch_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_forearm_roll_joint" type="revolute">
- <axis> 1 0 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_forearm_roll_joint" type="revolute">
+ <axis> 1 0 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_forearm_roll_inertial">
- <mass> 1.804155 </mass>
- <com> -0.000058 0.013779 0.179474 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012430552544 -0.000003671102 0.000029379389 0.013567548848 -0.000427679042 0.001755089866 </inertia>
- </define>
+ <define template="pr2_forearm_roll_inertial">
+ <mass> 1.804155 </mass>
+ <com> -0.000058 0.013779 0.179474 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012430552544 -0.000003671102 0.000029379389 0.013567548848 -0.000427679042 0.001755089866 </inertia>
+ </define>
- <define template="pr2_forearm_roll_visual">
- <xyz>forearm_roll_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size>forearm_roll_length forearm_roll_radius </size>
- </geometry>
- </define>
+ <define template="pr2_forearm_roll_visual">
+ <xyz>forearm_roll_length/2 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size>forearm_roll_length forearm_roll_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_wrist_pitch_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_wrist_pitch_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_wrist_pitch_inertial">
- <mass> 1.804155 </mass>
- <com> -0.000058 0.013779 0.179474 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012430552544 -0.000003671102 0.000029379389 0.013567548848 -0.000427679042 0.001755089866 </inertia>
- </define>
+ <define template="pr2_wrist_pitch_inertial">
+ <mass> 1.804155 </mass>
+ <com> -0.000058 0.013779 0.179474 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012430552544 -0.000003671102 0.000029379389 0.013567548848 -0.000427679042 0.001755089866 </inertia>
+ </define>
- <define template="pr2_wrist_pitch_visual">
- <xyz>0 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size>wrist_pitch_length wrist_pitch_radius </size>
- </geometry>
- </define>
+ <define template="pr2_wrist_pitch_visual">
+ <xyz>0 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size>wrist_pitch_length wrist_pitch_radius </size>
+ </geometry>
+ </define>
- <define template="pr2_wrist_roll_joint" type="revolute">
- <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
- </define>
+ <define template="pr2_wrist_roll_joint" type="revolute">
+ <axis> 0 1 0 </axis> <!-- direction of the joint in a global coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <calibration>1.5 -1 </calibration> <!-- Calibration stop/flag indicating location and then direction -->
+ </define>
- <define template="pr2_wrist_roll_inertial">
- <mass> 1.804155 </mass>
- <com> -0.000058 0.013779 0.179474 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia> 0.012430552544 -0.000003671102 0.000029379389 0.013567548848 -0.000427679042 0.001755089866 </inertia>
- </define>
+ <define template="pr2_wrist_roll_inertial">
+ <mass> 1.804155 </mass>
+ <com> -0.000058 0.013779 0.179474 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia> 0.012430552544 -0.000003671102 0.000029379389 0.013567548848 -0.000427679042 0.001755089866 </inertia>
+ </define>
- <define template="pr2_wrist_roll_visual">
- <xyz>0 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="cylinder">
- <size>wrist_roll_length wrist_roll_radius </size>
- </geometry>
- </define>
- </templates>
+ <define template="pr2_wrist_roll_visual">
+ <xyz>0 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="cylinder">
+ <size>wrist_roll_length wrist_roll_radius </size>
+ </geometry>
+ </define>
+ </templates>
<!-- End template definitions for ease of reuse -->
<!-- Begin base definition -->
- <link name="base"><!-- link specifying the base of the robot -->
+ <link name="base"><!-- link specifying the base of the robot -->
- <parent> world</parent>
+ <parent> world</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to a global coordinate frame -->
- <xyz> 0 0 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to the parent link's coordinate frame -->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to a global coordinate frame -->
+ <xyz> 0 0 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to the parent link's coordinate frame -->
- <joint type="floating" name="joint_base">
- <anchor>0.25 0.1 0.3 </anchor> <!-- Initial position of the base in a global coordinate frame -->
- </joint>
+ <joint type="floating" name="joint_base">
+ <anchor>0.25 0.1 0.3 </anchor> <!-- Initial position of the base in a global coordinate frame -->
+ </joint>
- <inertial>
- <mass> 70750.964 </mass>
- <com> -0.061523 0.000942 0.293569 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
- <inertia>5.652232699207 -0.009719934438 1.293988226423 5.669473158652 -0.007379583694 3.683196351726 </inertia>
- </inertial>
+ <inertial>
+ <mass> 70750.964 </mass>
+ <com> -0.061523 0.000942 0.293569 </com> <!-- position of the center of mass with respect to the link's own anchor in a local coordinate frame -->
+ <inertia>5.652232699207 -0.009719934438 1.293988226423 5.669473158652 -0.007379583694 3.683196351726 </inertia>
+ </inertial>
- <visual>
- <xyz>0 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="box">
- <size>base_length base_width base_height</size>
- </geometry>
- </visual>
+ <visual>
+ <xyz>0 0 0 </xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="box">
+ <size>base_length base_width base_height</size>
+ </geometry>
+ </visual>
- <collision>
- <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
- <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
- <material>Gazebo/Grey</material>
- <geometry type="box">
- <size>base_length base_width base_height</size>
- </geometry>
- </collision>
+ <collision>
+ <xyz>0 0 0</xyz> <!-- location defined with respect to the link origin in a local coordinate frame -->
+ <rpy>0.0 0.0 0.0 </rpy> <!-- All angles always in radians, yaw about Z axis, pitch about the Y axis and roll about the X axis -->
+ <material>Gazebo/Grey</material>
+ <geometry type="box">
+ <size>base_length base_width base_height</size>
+ </geometry>
+ </collision>
- </link>
+ </link>
- <link name="caster_front_left">
- <parent> base</parent>
+ <link name="caster_front_left">
+ <parent> base</parent>
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0.2255 0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <joint clone="pr2_caster_joint"/>
+ <inertial clone="pr2_caster_inertial"/>
+ <visual clone="pr2_caster_visual"/>
+ <collision clone="pr2_caster_visual"/>
+ </link>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0.2255 0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_caster_joint"/>
- <inertial clone="pr2_caster_inertial"/>
- <visual clone="pr2_caster_visual"/>
- <collision clone="pr2_caster_visual"/>
- </link>
+ <link name="caster_front_right">
+ <parent> base</parent>
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0.2255 -0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <joint clone="pr2_caster_joint"/>
+ <inertial clone="pr2_caster_inertial"/>
+ <visual clone="pr2_caster_visual"/>
+ <collision clone="pr2_caster_visual"/>
+ </link>
- <link name="caster_front_right">
- <parent> base</parent>
+ <link name="caster_rear_left">
+ <parent> base</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0.2255 -0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> -0.2255 0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_caster_joint"/>
- <inertial clone="pr2_caster_inertial"/>
- <visual clone="pr2_caster_visual"/>
- <collision clone="pr2_caster_visual"/>
- </link>
+ <joint clone="pr2_caster_joint"/>
+ <inertial clone="pr2_caster_inertial"/>
+ <visual clone="pr2_caster_visual"/>
+ <collision clone="pr2_caster_visual"/>
+ </link>
- <link name="caster_rear_left">
- <parent> base</parent>
+ <link name="caster_rear_right">
+ <parent> base</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> -0.2255 0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> -0.2255 -0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_caster_joint"/>
- <inertial clone="pr2_caster_inertial"/>
- <visual clone="pr2_caster_visual"/>
- <collision clone="pr2_caster_visual"/>
- </link>
+ <joint clone="pr2_caster_joint"/>
+ <inertial clone="pr2_caster_inertial"/>
+ <visual clone="pr2_caster_visual"/>
+ <collision clone="pr2_caster_visual"/>
+ </link>
- <link name="caster_rear_right">
- <parent> base</parent>
+ <link name="wheel_front_left_l">
+ <parent> caster_front_left</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> -0.2255 -0.2255 0.08069 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_caster_joint"/>
- <inertial clone="pr2_caster_inertial"/>
- <visual clone="pr2_caster_visual"/>
- <collision clone="pr2_caster_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_front_left_l">
- <parent> caster_front_left</parent>
+ <link name="wheel_front_left_r">
+ <parent> caster_front_left</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_front_left_r">
- <parent> caster_front_left</parent>
+ <link name="wheel_front_right_l">
+ <parent> caster_front_right</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_front_right_l">
- <parent> caster_front_right</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <link name="wheel_front_right_r">
+ <parent> caster_front_right</parent>
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_front_right_r">
- <parent> caster_front_right</parent>
+ <link name="wheel_rear_left_l">
+ <parent> caster_rear_left</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_rear_left_l">
- <parent> caster_rear_left</parent>
+ <link name="wheel_rear_left_r">
+ <parent> caster_rear_left</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_rear_left_r">
- <parent> caster_rear_left</parent>
+ <link name="wheel_rear_right_l">
+ <parent> caster_rear_right</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_rear_right_l">
- <parent> caster_rear_right</parent>
+ <link name="wheel_rear_right_r">
+ <parent> caster_rear_right</parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
+ <joint clone="pr2_wheel_joint"/>
+ <inertial clone="pr2_wheel_inertial"/>
+ <visual clone="pr2_wheel_visual"/>
+ <collision clone="pr2_wheel_visual"/>
+ </link>
- <link name="wheel_rear_right_r">
- <parent> caster_rear_right</parent>
-
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> 0 -0.049 0 </xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
-
- <joint clone="pr2_wheel_joint"/>
- <inertial clone="pr2_wheel_inertial"/>
- <visual clone="pr2_wheel_visual"/>
- <collision clone="pr2_wheel_visual"/>
- </link>
-
<!-- End base definition -->
<!-- Begin torso definition -->
- <link name="torso">
- <parent> base </parent>
- <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
- <xyz> -0.05 0 0</xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
+ <link name="torso">
+ <parent> base </parent>
+ <rpy> 0 0 0 </rpy> <!-- rotation of a local coordinate frame attached to the link with respect to the parent's frame -->
+ <xyz> -0.05 0 0</xyz> <!-- position of a local coordinate frame attached to the link with respect to parent's frame-->
- <joint type="prismatic">
- <axis> 0 0 1 </axis> <!-- direction of the joint in a local coordinate frame -->
- <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
- <limit> -0.030 0.396 </limit>
- </joint>
+ <joint type="prismatic">
+ <axis> 0 0 1 </axis> <!-- direction of the joint in a local coordinate frame -->
+ <anchor>0 0 0 </anchor> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit> -0.030 0.396 </limit>
+ </joint>
- <inertial>
- <mass> 36.248046 </mass>
- <com> -0.085285 -0.002393 -0.149724 </com> <!-- position of the center of mass wit...
[truncated message content] |