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
00038
00039
00040 #include <math.h>
00041 #include <pluginlib/class_list_macros.h>
00042 #include "pr2_mechanism_model/robot.h"
00043 #include "sr_mechanism_model/simple_transmission.h"
00044
00045 #include <sr_hardware_interface/sr_actuator.hpp>
00046
00047 using namespace pr2_hardware_interface;
00048
00049 PLUGINLIB_EXPORT_CLASS(sr_mechanism_model::SimpleTransmission, pr2_mechanism_model::Transmission)
00050
00051 namespace sr_mechanism_model
00052 {
00053 bool SimpleTransmission::initXml(TiXmlElement *elt, pr2_mechanism_model::Robot *robot)
00054 {
00055 const char *name = elt->Attribute("name");
00056 name_ = name ? name : "";
00057
00058 TiXmlElement *jel = elt->FirstChildElement("joint");
00059 const char *joint_name = jel ? jel->Attribute("name") : NULL;
00060 if (!joint_name)
00061 {
00062 ROS_ERROR("SimpleTransmission did not specify joint name");
00063 return false;
00064 }
00065
00066 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00067 if (!joint)
00068 {
00069 ROS_ERROR("SimpleTransmission could not find joint named \"%s\"", joint_name);
00070 return false;
00071 }
00072 joint_names_.push_back(joint_name);
00073
00074 TiXmlElement *ael = elt->FirstChildElement("actuator");
00075 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00076 pr2_hardware_interface::Actuator *a;
00077 if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00078 {
00079 ROS_ERROR("SimpleTransmission 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 mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00086
00087 return true;
00088 }
00089
00090 bool SimpleTransmission::initXml(TiXmlElement *elt)
00091 {
00092 const char *name = elt->Attribute("name");
00093 name_ = name ? name : "";
00094
00095 TiXmlElement *jel = elt->FirstChildElement("joint");
00096 const char *joint_name = jel ? jel->Attribute("name") : NULL;
00097 if (!joint_name)
00098 {
00099 ROS_ERROR("SimpleTransmission did not specify joint name");
00100 return false;
00101 }
00102 joint_names_.push_back(joint_name);
00103
00104 TiXmlElement *ael = elt->FirstChildElement("actuator");
00105 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00106 if (!actuator_name)
00107 {
00108 ROS_ERROR("SimpleTransmission could not find actuator named \"%s\"", actuator_name);
00109 return false;
00110 }
00111 actuator_names_.push_back(actuator_name);
00112
00113 mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00114
00115 return true;
00116 }
00117
00118 void SimpleTransmission::propagatePosition(
00119 std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00120 {
00121 ROS_DEBUG(" propagate position");
00122
00123 assert(as.size() == 1);
00124 assert(js.size() == 1);
00125 js[0]->position_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_;
00126 js[0]->velocity_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_;
00127 js[0]->measured_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_;
00128
00129 ROS_DEBUG("end propagate position");
00130 }
00131
00132 void SimpleTransmission::propagatePositionBackwards(
00133 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00134 {
00135 ROS_DEBUG(" propagate position bw");
00136
00137 assert(as.size() == 1);
00138 assert(js.size() == 1);
00139 static_cast<sr_actuator::SrActuator*>(as[0])->state_.position_ = js[0]->position_;
00140 static_cast<sr_actuator::SrActuator*>(as[0])->state_.velocity_ = js[0]->velocity_;
00141 static_cast<sr_actuator::SrActuator*>(as[0])->state_.last_measured_effort_ = js[0]->measured_effort_;
00142
00143
00144 if (! simulated_actuator_timestamp_initialized_)
00145 {
00146
00147 static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_ = ros::Duration(0);
00148
00149
00150 if (ros::isStarted())
00151 {
00152 simulated_actuator_start_time_ = ros::Time::now();
00153 simulated_actuator_timestamp_initialized_ = true;
00154 }
00155 }
00156 else
00157 {
00158
00159 static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00160 }
00161
00162 static_cast<sr_actuator::SrActuator*>(as[0])->state_.timestamp_ = static_cast<sr_actuator::SrActuator*>(as[0])->state_.sample_timestamp_.toSec();
00163
00164
00165 this->joint_calibration_simulator_.simulateJointCalibration(js[0],static_cast<sr_actuator::SrActuator*>(as[0]));
00166
00167 ROS_DEBUG(" end propagate position bw");
00168 }
00169
00170 void SimpleTransmission::propagateEffort(
00171 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00172 {
00173 ROS_DEBUG(" propagate effort");
00174
00175 assert(as.size() == 1);
00176 assert(js.size() == 1);
00177 static_cast<sr_actuator::SrActuator*>(as[0])->command_.enable_ = true;
00178 static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_ = js[0]->commanded_effort_;
00179
00180 ROS_DEBUG("end propagate effort");
00181 }
00182
00183 void SimpleTransmission::propagateEffortBackwards(
00184 std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00185 {
00186 ROS_DEBUG(" propagate effort bw");
00187
00188 assert(as.size() == 1);
00189 assert(js.size() == 1);
00190 js[0]->commanded_effort_ = static_cast<sr_actuator::SrActuator*>(as[0])->command_.effort_;
00191
00192 ROS_DEBUG("end propagate effort bw");
00193 }
00194
00195 }
00196
00197
00198
00199
00200
00201