77
88#include " IOBPlugin.h"
99
10+ #if __cplusplus >= 201103L
11+ #include < memory>
12+ using std::dynamic_pointer_cast;
13+ #else
14+ using boost::dynamic_pointer_cast;
15+ #endif
16+
1017namespace gazebo
1118{
1219GZ_REGISTER_MODEL_PLUGIN (IOBPlugin);
@@ -240,10 +247,10 @@ void IOBPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
240247 ROS_ERROR (" Force-Torque sensor: %s has invalid configuration" , sensor_name.c_str ());
241248 }
242249 // setup force sensor publishers
243- boost:: shared_ptr<std::vector<boost:: shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue (new std::vector<boost:: shared_ptr<geometry_msgs::WrenchStamped> >);
250+ shared_ptr<std::vector<shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue (new std::vector<shared_ptr<geometry_msgs::WrenchStamped> >);
244251 // forceValQueue->resize(this->force_sensor_average_window_size);
245252 for ( int i=0 ; i<this ->force_sensor_average_window_size ; i++ ){
246- boost:: shared_ptr<geometry_msgs::WrenchStamped> fbuf (new geometry_msgs::WrenchStamped);
253+ shared_ptr<geometry_msgs::WrenchStamped> fbuf (new geometry_msgs::WrenchStamped);
247254 forceValQueue->push_back (fbuf);
248255 }
249256 this ->forceValQueueMap [sensor_name] = forceValQueue;
@@ -275,7 +282,7 @@ void IOBPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
275282 gzerr << ln << " not found\n " ;
276283 } else {
277284 // Get imu sensors
278- msi.sensor = boost:: dynamic_pointer_cast<sensors::ImuSensor>
285+ msi.sensor = dynamic_pointer_cast<sensors::ImuSensor>
279286 (sensors::SensorManager::Instance ()->GetSensor
280287 (this ->world ->GetName () + " ::" + msi.link ->GetScopedName () + " ::" + msi.sensor_name ));
281288
@@ -377,7 +384,7 @@ void IOBPlugin::Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf) {
377384 // effort average
378385 effortValQueue.resize (0 );
379386 for (int i = 0 ; i < this ->effort_average_window_size ; i++) {
380- boost:: shared_ptr<std::vector<double > > vbuf (new std::vector<double > (this ->joints .size ()));
387+ shared_ptr<std::vector<double > > vbuf (new std::vector<double > (this ->joints .size ()));
381388 effortValQueue.push_back (vbuf);
382389 }
383390 // for reference
@@ -779,7 +786,7 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
779786 // populate robotState from robot
780787 this ->robotState .header .stamp = ros::Time (_curTime.sec , _curTime.nsec );
781788
782- boost:: shared_ptr<std::vector<double > > vbuf = effortValQueue.at (this ->effort_average_cnt );
789+ shared_ptr<std::vector<double > > vbuf = effortValQueue.at (this ->effort_average_cnt );
783790 // joint states
784791 for (unsigned int i = 0 ; i < this ->joints .size (); ++i) {
785792 this ->robotState .position [i] = this ->joints [i]->GetAngle (0 ).Radian ();
@@ -809,7 +816,7 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
809816 }
810817 if (this ->use_joint_effort ) {
811818 for (int j = 0 ; j < effortValQueue.size (); j++) {
812- boost:: shared_ptr<std::vector<double > > vbuf = effortValQueue.at (j);
819+ shared_ptr<std::vector<double > > vbuf = effortValQueue.at (j);
813820 for (int i = 0 ; i < this ->joints .size (); i++) {
814821 this ->robotState .effort [i] += vbuf->at (i);
815822 }
@@ -828,8 +835,8 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
828835 this ->robotState .sensors .resize (this ->forceSensorNames .size ());
829836 for (unsigned int i = 0 ; i < this ->forceSensorNames .size (); i++) {
830837 forceSensorMap::iterator it = this ->forceSensors .find (this ->forceSensorNames [i]);
831- boost:: shared_ptr<std::vector<boost:: shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue = this ->forceValQueueMap .find (this ->forceSensorNames [i])->second ;
832- boost:: shared_ptr<geometry_msgs::WrenchStamped> forceVal = forceValQueue->at (this ->force_sensor_average_cnt );
838+ shared_ptr<std::vector<shared_ptr<geometry_msgs::WrenchStamped> > > forceValQueue = this ->forceValQueueMap .find (this ->forceSensorNames [i])->second ;
839+ shared_ptr<geometry_msgs::WrenchStamped> forceVal = forceValQueue->at (this ->force_sensor_average_cnt );
833840 if (it != this ->forceSensors .end ()) {
834841 physics::JointPtr jt = it->second .joint ;
835842 if (!!jt) {
@@ -868,7 +875,7 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
868875 this ->robotState .sensors [i].torque .y = 0 ;
869876 this ->robotState .sensors [i].torque .z = 0 ;
870877 for ( int j=0 ; j<forceValQueue->size () ; j++ ){
871- boost:: shared_ptr<geometry_msgs::WrenchStamped> forceValBuf = forceValQueue->at (j);
878+ shared_ptr<geometry_msgs::WrenchStamped> forceValBuf = forceValQueue->at (j);
872879 this ->robotState .sensors [i].force .x += forceValBuf->wrench .force .x ;
873880 this ->robotState .sensors [i].force .y += forceValBuf->wrench .force .y ;
874881 this ->robotState .sensors [i].force .z += forceValBuf->wrench .force .z ;
@@ -897,9 +904,15 @@ void IOBPlugin::GetRobotStates(const common::Time &_curTime){
897904 if (!!sp) {
898905 this ->robotState .Imus [i].name = this ->imuSensorNames [i];
899906 this ->robotState .Imus [i].frame_id = it->second .frame_id ;
907+ #if __cplusplus >= 201103L
908+ math::Vector3 wLocal = sp->AngularVelocity ();
909+ math::Vector3 accel = sp->LinearAcceleration ();
910+ math::Quaternion imuRot = sp->Orientation ();
911+ #else
900912 math::Vector3 wLocal = sp->GetAngularVelocity ();
901913 math::Vector3 accel = sp->GetLinearAcceleration ();
902914 math::Quaternion imuRot = sp->GetOrientation ();
915+ #endif
903916 this ->robotState .Imus [i].angular_velocity .x = wLocal.x ;
904917 this ->robotState .Imus [i].angular_velocity .y = wLocal.y ;
905918 this ->robotState .Imus [i].angular_velocity .z = wLocal.z ;
@@ -948,7 +961,11 @@ void IOBPlugin::UpdatePID_Velocity_Control(double _dt) {
948961 static_cast <double >(this ->robotState .kpv_velocity [i]) * this ->errorTerms [i].qd_p ;
949962
950963 // update max force
964+ #if __cplusplus >= 201103L
965+ this ->joints [i]->SetParam (" max_force" , 0 , this ->joints [i]->GetEffortLimit (0 ));
966+ #else
951967 this ->joints [i]->SetMaxForce (0 , this ->joints [i]->GetEffortLimit (0 ));
968+ #endif
952969 // clamp max velocity
953970 j_velocity = math::clamp (j_velocity, -max_vel, max_vel);
954971#if 0
0 commit comments