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_for_muscle.hpp"
00044
00045 #include <sr_hardware_interface/sr_actuator.hpp>
00046
00047 using namespace pr2_hardware_interface;
00048
00049 PLUGINLIB_EXPORT_CLASS(sr_mechanism_model::SimpleTransmissionForMuscle, pr2_mechanism_model::Transmission)
00050
00051 namespace sr_mechanism_model
00052 {
00053 bool SimpleTransmissionForMuscle::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("SimpleTransmissionForMuscle 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("SimpleTransmissionForMuscle 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("SimpleTransmissionForMuscle 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 SimpleTransmissionForMuscle::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("SimpleTransmissionForMuscle 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("SimpleTransmissionForMuscle 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 SimpleTransmissionForMuscle::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::SrMuscleActuator*>(as[0])->state_.position_;
00126 js[0]->velocity_ = static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.velocity_;
00127
00128
00129
00130
00131
00132 js[0]->measured_effort_ = (static_cast<double>(static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.pressure_[1]) * 0x10000) +
00133 static_cast<double>(static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.pressure_[0]);
00134
00135 ROS_DEBUG("end propagate position");
00136 }
00137
00138 void SimpleTransmissionForMuscle::propagatePositionBackwards(
00139 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00140 {
00141 ROS_DEBUG(" propagate position bw");
00142
00143 assert(as.size() == 1);
00144 assert(js.size() == 1);
00145 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.position_ = js[0]->position_;
00146 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.velocity_ = js[0]->velocity_;
00147 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.last_measured_effort_ = js[0]->measured_effort_;
00148
00149
00150 if (! simulated_actuator_timestamp_initialized_)
00151 {
00152
00153 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.sample_timestamp_ = ros::Duration(0);
00154
00155
00156 if (ros::isStarted())
00157 {
00158 simulated_actuator_start_time_ = ros::Time::now();
00159 simulated_actuator_timestamp_initialized_ = true;
00160 }
00161 }
00162 else
00163 {
00164
00165 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00166 }
00167
00168 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.timestamp_ = static_cast<sr_actuator::SrMuscleActuator*>(as[0])->state_.sample_timestamp_.toSec();
00169
00170
00171 this->joint_calibration_simulator_.simulateJointCalibration(js[0],static_cast<sr_actuator::SrMuscleActuator*>(as[0]));
00172
00173 ROS_DEBUG(" end propagate position bw");
00174 }
00175
00176 void SimpleTransmissionForMuscle::propagateEffort(
00177 std::vector<pr2_mechanism_model::JointState*>& js, std::vector<pr2_hardware_interface::Actuator*>& as)
00178 {
00179 ROS_DEBUG(" propagate effort");
00180
00181 assert(as.size() == 1);
00182 assert(js.size() == 1);
00183 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->command_.enable_ = true;
00184
00185
00186
00187
00188
00189 double valve_0 = fmod(js[0]->commanded_effort_, 0x10);
00190 int8_t valve_0_tmp = static_cast<int8_t>(valve_0 + 0.5);
00191 if (valve_0_tmp >= 8)
00192 {
00193 valve_0_tmp -= 8;
00194 valve_0_tmp *= (-1);
00195 }
00196
00197 int8_t valve_1_tmp = static_cast<int8_t>(((fmod(js[0]->commanded_effort_, 0x100) - valve_0) / 0x10) + 0.5);
00198 if (valve_1_tmp >= 8)
00199 {
00200 valve_1_tmp -= 8;
00201 valve_1_tmp *= (-1);
00202 }
00203
00204 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->command_.valve_[0] = valve_0_tmp;
00205 static_cast<sr_actuator::SrMuscleActuator*>(as[0])->command_.valve_[1] = valve_1_tmp;
00206
00207 ROS_DEBUG("end propagate effort");
00208 }
00209
00210 void SimpleTransmissionForMuscle::propagateEffortBackwards(
00211 std::vector<pr2_hardware_interface::Actuator*>& as, std::vector<pr2_mechanism_model::JointState*>& js)
00212 {
00213 ROS_DEBUG(" propagate effort bw");
00214
00215 assert(as.size() == 1);
00216 assert(js.size() == 1);
00217 js[0]->commanded_effort_ = static_cast<sr_actuator::SrMuscleActuator*>(as[0])->command_.effort_;
00218
00219 ROS_DEBUG("end propagate effort bw");
00220 }
00221
00222 }
00223
00224
00225
00226
00227
00228