Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <math.h>
00038 #include <pluginlib/class_list_macros.h>
00039 #include "pr2_mechanism_model/robot.h"
00040 #include "pr2_examples_gazebo/spring_transmission.h"
00041 #include <angles/angles.h>
00042
00043 using namespace pr2_examples_gazebo;
00044 using namespace pr2_hardware_interface;
00045
00046 PLUGINLIB_DECLARE_CLASS(pr2_examples_gazebo, SpringTransmission,
00047 pr2_examples_gazebo::SpringTransmission,
00048 pr2_mechanism_model::Transmission)
00049
00050
00051 bool SpringTransmission::initXml(TiXmlElement *elt, pr2_mechanism_model::Robot *robot)
00052 {
00053 const char *name = elt->Attribute("name");
00054 name_ = name ? name : "";
00055
00056 TiXmlElement *jel = elt->FirstChildElement("joint");
00057 const char *joint_name = jel ? jel->Attribute("name") : NULL;
00058 if (!joint_name)
00059 {
00060 ROS_ERROR("SpringTransmission did not specify joint name");
00061 return false;
00062 }
00063
00064 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00065 if (!joint)
00066 {
00067 ROS_ERROR("SpringTransmission could not find joint named \"%s\"", joint_name);
00068 return false;
00069 }
00070 joint_names_.push_back(joint_name);
00071
00072
00073
00074 TiXmlElement *ael = elt->FirstChildElement("actuator");
00075 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00076 Actuator *a;
00077 if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00078 {
00079 ROS_ERROR("SpringTransmission could not find actuator named \"%s\"", actuator_name);
00080 return false;
00081 }
00082 a->command_.enable_ = true;
00083 actuator_names_.push_back(actuator_name);
00084
00085
00086
00087
00088 spring_stiffness_ = atof(elt->FirstChildElement("springStiffness")->GetText());
00089
00090 return true;
00091 }
00092
00093 void SpringTransmission::propagatePosition(
00094 std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00095 {
00096
00097 assert(as.size() == 1);
00098 assert(js.size() == 1);
00099 js[0]->position_ = as[0]->state_.position_;
00100 js[0]->velocity_ = as[0]->state_.velocity_;
00101 js[0]->measured_effort_ = as[0]->state_.last_measured_effort_;
00102 }
00103
00104 void SpringTransmission::propagatePositionBackwards(
00105 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00106 {
00107 assert(as.size() == 1);
00108 assert(js.size() == 1);
00109 as[0]->state_.position_ = js[0]->position_;
00110 as[0]->state_.velocity_ = js[0]->velocity_;
00111 as[0]->state_.last_measured_effort_ = js[0]->measured_effort_;
00112 }
00113
00114 void SpringTransmission::propagateEffort(
00115 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<Actuator*>& as)
00116 {
00117 assert(as.size() == 1);
00118 assert(js.size() == 1);
00119 as[0]->command_.effort_ = -spring_stiffness_ * js[0]->position_;
00120 }
00121
00122 void SpringTransmission::propagateEffortBackwards(
00123 std::vector<Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00124 {
00125 assert(as.size() == 1);
00126 assert(js.size() == 1);
00127 js[0]->commanded_effort_ = as[0]->command_.effort_;
00128 }
00129