Tetrapod Project
tetrapod_plugin.cpp
Go to the documentation of this file.
1 /*******************************************************************/
2 /* AUTHOR: Paal Arthur S. Thorseth */
3 /* ORGN: Dept of Eng Cybernetics, NTNU Trondheim */
4 /* FILE: tetrapod_plugin.cpp */
5 /* DATE: Feb 4, 2021 */
6 /* */
7 /* Copyright (C) 2021 Paal Arthur S. Thorseth, */
8 /* Adrian B. Ghansah */
9 /* */
10 /* This program is free software: you can redistribute it */
11 /* and/or modify it under the terms of the GNU General */
12 /* Public License as published by the Free Software Foundation, */
13 /* either version 3 of the License, or (at your option) any */
14 /* later version. */
15 /* */
16 /* This program is distributed in the hope that it will be useful, */
17 /* but WITHOUT ANY WARRANTY; without even the implied warranty */
18 /* of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. */
19 /* See the GNU General Public License for more details. */
20 /* */
21 /* You should have received a copy of the GNU General Public */
22 /* License along with this program. If not, see */
23 /* <https://www.gnu.org/licenses/>. */
24 /* */
25 /*******************************************************************/
26 
27 
29 
30 
31 namespace gazebo {
32 
33 // Constructor
35 
36 // Destructor
38 {
39  this->rosNode->shutdown();
40 
41  this->rosProcessQueue.clear();
42  this->rosProcessQueue.disable();
43  this->rosProcessQueueThread.join();
44 
45  this->rosPublishQueue.clear();
46  this->rosPublishQueue.disable();
47  this->rosPublishQueueThread.join();
48 }
49 
50 // Load Plugin
51 void TetrapodPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
52 {
53  // Store model pointer
54  this->model = _model;
55 
56  // Store world pointer
57  this->world = _model->GetWorld();
58 
59  // Store model name
60  this->model_name = _model->GetName();
61  // ROS_INFO_STREAM("Model name: " << model_name); TODO REMOVE
62 
63  // Store base link
64  this->base = _model->GetLink(this->model_name + "::tetrapod::body");
65 
66  // Store joints
67  this->joints = this->model->GetJointController()->GetJoints();
68  //printMap(joints); TODO remove
69 
70  for (auto& t: joints)
71  {
72  ROS_INFO_STREAM(t.first);
73  }
74 
75  // Initialize ROS
76  InitRos();
77 
78  // Load parameters from config
79  if (!LoadParametersRos())
80  {
81  ROS_ERROR("Could not load parameters.");
82  return;
83  }
84 
85  // Setup Joint Controllers
87 
88  // Configure initial joint states
90 
91  // Initialize ROS Queue Threads
93 }
94 
95 // Get base pose
96 Eigen::Matrix<double, 6, 1> TetrapodPlugin::GetBasePose()
97 {
98  ignition::math::Pose3d base_pose = this->base->WorldPose();
99 
100  Eigen::Matrix<double, 6, 1> q_b;
101 
102  q_b(0) = base_pose.X();
103  q_b(1) = base_pose.Y();
104  q_b(2) = base_pose.Z();
105  q_b(3) = base_pose.Roll();
106  q_b(4) = base_pose.Pitch();
107  q_b(5) = base_pose.Yaw();
108 
109  return q_b;
110 }
111 
112 // Get base twist
113 Eigen::Matrix<double, 6, 1> TetrapodPlugin::GetBaseTwist()
114 {
115  ignition::math::Vector3d base_linear_velocity = this->base->WorldLinearVel();
116 
117  ignition::math::Vector3d base_angular_velocity = this->base->WorldAngularVel();
118 
119  Eigen::Matrix<double, 6, 1> u_b;
120 
121  u_b(0) = base_linear_velocity.X();
122  u_b(1) = base_linear_velocity.Y();
123  u_b(2) = base_linear_velocity.Z();
124  u_b(3) = base_angular_velocity.X();
125  u_b(4) = base_angular_velocity.Y();
126  u_b(5) = base_angular_velocity.Z();
127 
128  return u_b;
129 }
130 
131 // Get joint force at _joint_name
132 // TODO Implement.
133 double TetrapodPlugin::GetJointForce(const std::string &_joint_name)
134 {
135  //this->joints[joint_name]-A map<joint_name, force> that contains force values set by the user of the JointController.
136 
137  double force = this->joints[this->model_name + "::" + _joint_name]->GetForce(0);
138  //std::map<std::string, double> force_map = this->model->GetJointController()->GetForces();
139 
140  //double force = force_map[this->model_name + "::" + _joint_name];
141 
142  return force;
143 }
144 
145 // Get joint forces
146 Eigen::Matrix<double, 12, 1> TetrapodPlugin::GetJointForces()
147 {
148  Eigen::Matrix<double, 12, 1> tau_r;
149 
150  // Front left
151  tau_r(0) = this->GetJointForce(this->joint_names[0]);
152  tau_r(1) = this->GetJointForce(this->joint_names[1]);
153  tau_r(2) = this->GetJointForce(this->joint_names[2]);
154 
155  // Front right
156  tau_r(3) = this->GetJointForce(this->joint_names[3]);
157  tau_r(4) = this->GetJointForce(this->joint_names[4]);
158  tau_r(5) = this->GetJointForce(this->joint_names[5]);
159 
160  // Rear left
161  tau_r(6) = this->GetJointForce(this->joint_names[6]);
162  tau_r(7) = this->GetJointForce(this->joint_names[7]);
163  tau_r(8) = this->GetJointForce(this->joint_names[8]);
164 
165  // Rear right
166  tau_r(9) = this->GetJointForce(this->joint_names[9]);
167  tau_r(10) = this->GetJointForce(this->joint_names[10]);
168  tau_r(11) = this->GetJointForce(this->joint_names[11]);
169 
170  return tau_r;
171 }
172 
173 // Get joint velocity at _joint_name
174 double TetrapodPlugin::GetJointVelocity(const std::string &_joint_name)
175 {
176  double vel = this->joints[this->model_name + "::" + _joint_name]->GetVelocity(0);
177 
178  return vel;
179 }
180 
181 // Get joint velocities
182 Eigen::Matrix<double, 12, 1> TetrapodPlugin::GetJointVelocities()
183 {
184  Eigen::Matrix<double, 12, 1> dot_q_r;
185 
186  // Front left
187  dot_q_r(0) = this->GetJointVelocity(this->joint_names[0]);
188  dot_q_r(1) = this->GetJointVelocity(this->joint_names[1]);
189  dot_q_r(2) = this->GetJointVelocity(this->joint_names[2]);
190 
191  // Front right
192  dot_q_r(3) = this->GetJointVelocity(this->joint_names[3]);
193  dot_q_r(4) = this->GetJointVelocity(this->joint_names[4]);
194  dot_q_r(5) = this->GetJointVelocity(this->joint_names[5]);
195 
196  // Rear left
197  dot_q_r(6) = this->GetJointVelocity(this->joint_names[6]);
198  dot_q_r(7) = this->GetJointVelocity(this->joint_names[7]);
199  dot_q_r(8) = this->GetJointVelocity(this->joint_names[8]);
200 
201  // Rear right
202  dot_q_r(9) = this->GetJointVelocity(this->joint_names[9]);
203  dot_q_r(10) = this->GetJointVelocity(this->joint_names[10]);
204  dot_q_r(11) = this->GetJointVelocity(this->joint_names[11]);
205 
206  return dot_q_r;
207 }
208 
209 // Get joint position at _joint_name
210 double TetrapodPlugin::GetJointPosition(const std::string &_joint_name)
211 {
212  double pos = this->joints[this->model_name + "::" + _joint_name]->Position();
213 
214  return pos;
215 }
216 
217 // Get joint positions
218 Eigen::Matrix<double, 12, 1> TetrapodPlugin::GetJointPositions()
219 {
220  Eigen::Matrix<double, 12, 1> q_r;
221 
222  // Front left
223  q_r(0) = this->GetJointPosition(this->joint_names[0]);
224  q_r(1) = this->GetJointPosition(this->joint_names[1]);
225  q_r(2) = this->GetJointPosition(this->joint_names[2]);
226 
227  // Front right
228  q_r(3) = this->GetJointPosition(this->joint_names[3]);
229  q_r(4) = this->GetJointPosition(this->joint_names[4]);
230  q_r(5) = this->GetJointPosition(this->joint_names[5]);
231 
232  // Rear left
233  q_r(6) = this->GetJointPosition(this->joint_names[6]);
234  q_r(7) = this->GetJointPosition(this->joint_names[7]);
235  q_r(8) = this->GetJointPosition(this->joint_names[8]);
236 
237  // Rear right
238  q_r(9) = this->GetJointPosition(this->joint_names[9]);
239  q_r(10) = this->GetJointPosition(this->joint_names[10]);
240  q_r(11) = this->GetJointPosition(this->joint_names[11]);
241 
242  return q_r;
243 }
244 
245 
246 // Apply force at a single joint
247 void TetrapodPlugin::SetJointForce(const std::string &_joint_name, const double &_force)
248 {
249  this->model->GetJointController()->SetForce(
250  this->model_name + "::" + _joint_name,
251  _force
252  );
253 }
254 
255 // Apply joint forces
256 void TetrapodPlugin::SetJointForces(const std::vector<double> &_forces)
257 {
258  auto start = std::chrono::steady_clock::now();
259 
260  if (this->controlMode != 3)
261  {
262  this->model->GetJointController()->Reset();
263 
265  }
266 
267  for (size_t i = 0; i < this->joint_names.size(); i++)
268  {
269  this->model->GetJointController()->SetForce(
270  this->model_name + "::" + this->joint_names[i],
271  _forces[i]
272  );
273  }
274 
275  auto end = std::chrono::steady_clock::now();
276 
277  std::chrono::duration<double,std::micro> diff = end - start;
278 
279  ROS_DEBUG_STREAM("Time spent resetting commands and applying torques: " << diff.count() << " microseconds.");
280 }
281 
282 // Set the a single joints target velocity
283 void TetrapodPlugin::SetJointVelocity(const std::string &_joint_name, const double &_vel)
284 {
285  this->model->GetJointController()->SetVelocityTarget(
286  this->model_name + "::" + _joint_name,
287  _vel
288  );
289 }
290 
291 // Set joint target velocities
292 void TetrapodPlugin::SetJointVelocities(const std::vector<double> &_vel)
293 {
294  auto start = std::chrono::steady_clock::now();
295 
296  if (this->controlMode != 2)
297  {
298  this->model->GetJointController()->Reset();
299 
301  }
302 
303  for (size_t i = 0; i < this->joint_names.size(); i++)
304  {
305  this->model->GetJointController()->SetVelocityTarget(
306  this->model_name + "::" + this->joint_names[i],
307  _vel[i]
308  );
309  }
310 
311  auto end = std::chrono::steady_clock::now();
312 
313  std::chrono::duration<double,std::micro> diff = end - start;
314 
315  ROS_DEBUG_STREAM("Time spent resetting commands and setting velocity targets: " << diff.count() << " microseconds.");
316 }
317 
318 // Set the a single joints target position
319 void TetrapodPlugin::SetJointPosition(const std::string &_joint_name, const double &_pos)
320 {
321  this->model->GetJointController()->SetPositionTarget(
322  this->model_name + "::" + _joint_name,
323  _pos
324  );
325 }
326 
327 // Set joint target positions
328 void TetrapodPlugin::SetJointPositions(const std::vector<double> &_pos)
329 {
330  auto start = std::chrono::steady_clock::now();
331 
332  if (this->controlMode != 1)
333  {
334  this->model->GetJointController()->Reset();
335 
337  }
338 
339  for (size_t i = 0; i < this->joint_names.size(); i++)
340  {
341  this->model->GetJointController()->SetPositionTarget(
342  this->model_name + "::" + this->joint_names[i],
344  );
345  }
346 
347  auto end = std::chrono::steady_clock::now();
348 
349  std::chrono::duration<double,std::micro> diff = end - start;
350 
351  ROS_DEBUG_STREAM("Time spent resetting commands and setting position targets: " << diff.count() << " microseconds.");
352 }
353 
354 // Callback for ROS Joint State messages
355 void TetrapodPlugin::OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
356 {
357  if ((!_msg->position.empty()) && (_msg->position.size() == NUMJOINTS))
358  {
359  this->SetJointPositions(_msg->position);
360  }
361 
362  if ((!_msg->velocity.empty()) && (_msg->velocity.size() == NUMJOINTS))
363  {
364  this->SetJointVelocities(_msg->velocity);
365  }
366 
367  if ((!_msg->effort.empty()) && (_msg->effort.size() == NUMJOINTS))
368  {
369  this->SetJointForces(_msg->effort);
370  }
371 }
372 
373 // Callback for ROS Joint State messages
374 void TetrapodPlugin::OnFlJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
375 {
376  if ((!_msg->position.empty()) && (_msg->position.size() == 3))
377  {
378  this->SetJointPosition(this->joint_names[0], _msg->position[0]);
379  this->SetJointPosition(this->joint_names[1], _msg->position[1]);
380  this->SetJointPosition(this->joint_names[2], _msg->position[2]);
381  }
382 
383  if ((!_msg->velocity.empty()) && (_msg->velocity.size() == 3))
384  {
385  this->SetJointVelocity(this->joint_names[0], _msg->velocity[0]);
386  this->SetJointVelocity(this->joint_names[1], _msg->velocity[1]);
387  this->SetJointVelocity(this->joint_names[2], _msg->velocity[2]);
388  }
389 
390  if ((!_msg->effort.empty()) && (_msg->effort.size() == 3))
391  {
392  this->SetJointForce(this->joint_names[0], _msg->effort[0]);
393  this->SetJointForce(this->joint_names[1], _msg->effort[1]);
394  this->SetJointForce(this->joint_names[2], _msg->effort[2]);
395  }
396 }
397 
398 // Callback for ROS Force messages
399 void TetrapodPlugin::OnForceMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
400 {
401  this->SetJointForces(_msg->data);
402 }
403 
404 // Callback for ROS Velocity messages
405 void TetrapodPlugin::OnVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
406 {
407  this->SetJointVelocities(_msg->data);
408 }
409 
410 // Callback for ROS Position messages
411 void TetrapodPlugin::OnPosMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
412 {
413  this->SetJointPositions(_msg->data);
414 }
415 
416 // Setup thread to process messages
418 {
419  static const double timeout = 0.000001;
420  while (this->rosNode->ok())
421  {
422  this->rosProcessQueue.callAvailable(ros::WallDuration(timeout));
423  }
424 }
425 
426 // Setup thread to process messages
428 {
429  ros::Rate loop_rate(200);
430  while (this->rosNode->ok())
431  {
432  Eigen::Matrix<double, 18, 1> q; // generalized coordinates
433  Eigen::Matrix<double, 18, 1> u; // generalized velocities
434  Eigen::Matrix<double, 12, 1> tau; // joint forces (torques)
435 
436  q.block(0,0,5,0) << this->GetBasePose();
437  q.block(6,0,17,0) << this->GetJointPositions();
438 
439  u.block(0,0,5,0) << this->GetBaseTwist();
440  u.block(6,0,17,0) << this->GetJointVelocities();
441 
442  tau = this->GetJointForces();
443 
444  std_msgs::Float64MultiArray gen_coord_msg;
445  std_msgs::Float64MultiArray gen_vel_msg;
446  std_msgs::Float64MultiArray base_pose_msg;
447  std_msgs::Float64MultiArray base_twist_msg;
448  std_msgs::Float64MultiArray joint_forces_msg;
449  sensor_msgs::JointState joint_state_msg;
450 
451  tf::matrixEigenToMsg(q, gen_coord_msg);
452  tf::matrixEigenToMsg(u, gen_vel_msg);
453  tf::matrixEigenToMsg(tau, joint_forces_msg);
454 
455  tf::matrixEigenToMsg(q.topRows(6), base_pose_msg);
456  tf::matrixEigenToMsg(u.topRows(6), base_twist_msg);
457 
458  joint_state_msg.header.stamp = ros::Time::now();
459  for(int i = 0; i < 12; i++)
460  {
461  joint_state_msg.position.push_back(q(i + 6));
462  joint_state_msg.velocity.push_back(u(i + 6));
463  joint_state_msg.effort.push_back(tau(i));
464  }
465 
466  this->genCoordPub.publish(gen_coord_msg);
467  this->genVelPub.publish(gen_vel_msg);
468  this->basePosePub.publish(base_pose_msg);
469  this->baseTwistPub.publish(base_twist_msg);
470  this->jointForcesPub.publish(joint_forces_msg);
471  this->jointStatePub.publish(joint_state_msg);
472 
473  loop_rate.sleep();
474  }
475 }
476 
477 // Initialize ROS
479 {
480  if (!ros::isInitialized())
481  {
482  int argc = 0;
483  char **argv = NULL;
484  ros::init(
485  argc,
486  argv,
487  "gazebo_client",
488  ros::init_options::NoSigintHandler
489  );
490  }
491 
492  this->rosNode.reset(new ros::NodeHandle("gazebo_client"));
493 
494  ros::AdvertiseServiceOptions reset_simulation_aso =
495  ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
496  "/" + this->model->GetName() + "/reset_simulation",
497  boost::bind(&TetrapodPlugin::ResetSimulation, this, _1, _2),
498  ros::VoidPtr(),
499  &this->rosProcessQueue
500  );
501 
502  ros::AdvertiseOptions gen_coord_ao =
503  ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
504  "/" + this->model->GetName() + "/gen_coord",
505  1,
506  ros::SubscriberStatusCallback(),
507  ros::SubscriberStatusCallback(),
508  ros::VoidPtr(),
509  &this->rosPublishQueue
510  );
511 
512  ros::AdvertiseOptions gen_vel_ao =
513  ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
514  "/" + this->model->GetName() + "/gen_vel",
515  1,
516  ros::SubscriberStatusCallback(),
517  ros::SubscriberStatusCallback(),
518  ros::VoidPtr(),
519  &this->rosPublishQueue
520  );
521 
522  ros::AdvertiseOptions base_pose_so =
523  ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
524  "/" + this->model->GetName() + "/base_pose",
525  1,
526  ros::SubscriberStatusCallback(),
527  ros::SubscriberStatusCallback(),
528  ros::VoidPtr(),
529  &this->rosPublishQueue
530  );
531 
532  ros::AdvertiseOptions base_twist_so =
533  ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
534  "/" + this->model->GetName() + "/base_twist",
535  1,
536  ros::SubscriberStatusCallback(),
537  ros::SubscriberStatusCallback(),
538  ros::VoidPtr(),
539  &this->rosPublishQueue
540  );
541 
542  ros::AdvertiseOptions joint_forces_ao =
543  ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
544  "/" + this->model->GetName() + "/joint_forces",
545  1,
546  ros::SubscriberStatusCallback(),
547  ros::SubscriberStatusCallback(),
548  ros::VoidPtr(),
549  &this->rosPublishQueue
550  );
551 
552  ros::AdvertiseOptions joint_state_ao =
553  ros::AdvertiseOptions::create<sensor_msgs::JointState>
554  (
555  "/" + this->model->GetName() + "/joint_state",
556  1,
557  ros::SubscriberStatusCallback(),
558  ros::SubscriberStatusCallback(),
559  ros::VoidPtr(),
560  &this->rosPublishQueue
561  );
562 
563  ros::SubscribeOptions joint_state_cmd_so =
564  ros::SubscribeOptions::create<sensor_msgs::JointState>(
565  "/" + this->model->GetName() + "/joint_state_cmd",
566  1,
567  boost::bind(&TetrapodPlugin::OnJointStateMsg, this, _1),
568  ros::VoidPtr(),
569  &this->rosProcessQueue
570  );
571 
572  ros::SubscribeOptions force_so =
573  ros::SubscribeOptions::create<std_msgs::Float64MultiArray>(
574  "/" + this->model->GetName() + "/force_cmd",
575  1,
576  boost::bind(&TetrapodPlugin::OnForceMsg, this, _1),
577  ros::VoidPtr(),
578  &this->rosProcessQueue
579  );
580 
581  ros::SubscribeOptions vel_so =
582  ros::SubscribeOptions::create<std_msgs::Float64MultiArray>(
583  "/" + this->model->GetName() + "/vel_cmd",
584  1,
585  boost::bind(&TetrapodPlugin::OnVelMsg, this, _1),
586  ros::VoidPtr(),
587  &this->rosProcessQueue
588  );
589 
590  ros::SubscribeOptions pos_so =
591  ros::SubscribeOptions::create<std_msgs::Float64MultiArray>(
592  "/" + this->model->GetName() + "/pos_cmd",
593  1,
594  boost::bind(&TetrapodPlugin::OnPosMsg, this, _1),
595  ros::VoidPtr(),
596  &this->rosProcessQueue
597  );
598 
599  this->resetSimService = this->rosNode->advertiseService(reset_simulation_aso);
600 
601  this->genCoordPub = this->rosNode->advertise(gen_coord_ao);
602 
603  this->genVelPub = this->rosNode->advertise(gen_vel_ao);
604 
605  this->basePosePub = this->rosNode->advertise(base_pose_so);
606 
607  this->baseTwistPub = this->rosNode->advertise(base_twist_so);
608 
609  this->jointForcesPub = this->rosNode->advertise(joint_forces_ao);
610 
611  this->jointStatePub = this->rosNode->advertise(joint_state_ao);
612 
613  this->jointStateCmdSub = this->rosNode->subscribe(joint_state_cmd_so);
614 
615  this->forceSub = this->rosNode->subscribe(force_so);
616 
617  this->velSub = this->rosNode->subscribe(vel_so);
618 
619  this->posSub = this->rosNode->subscribe(pos_so);
620 
621 }
622 
623 // Initialize ROS Publish and Process Queue Threads
625 {
626  this->rosPublishQueueThread = std::thread(
627  std::bind(&TetrapodPlugin::PublishQueueThread, this)
628  );
629 
630  this->rosProcessQueueThread = std::thread(
631  std::bind(&TetrapodPlugin::ProcessQueueThread, this)
632  );
633 }
634 
635 // Load configuration
637 {
638  if (!this->rosNode->getParam("joint_names", this->joint_names))
639  {
640  ROS_ERROR("Could not read joint names from parameter server.");
641  return false;
642  }
643 
644  if (!this->rosNode->getParam("joint_config", this->joint_config))
645  {
646  ROS_ERROR("Could not read joint config from parameter server.");
647  return false;
648  }
649 
650  if (!this->rosNode->getParam("joint_velocity_controller/p_gains", this->vel_p_gains))
651  {
652  ROS_ERROR("Could not read velocity P-gains from parameter server.");
653  return false;
654  }
655 
656  if (!this->rosNode->getParam("joint_velocity_controller/i_gains", this->vel_i_gains))
657  {
658  ROS_ERROR("Could not read velocity I-gains from parameter server.");
659  return false;
660  }
661 
662  if (!this->rosNode->getParam("joint_velocity_controller/d_gains", this->vel_d_gains))
663  {
664  ROS_ERROR("Could not read velocity D-gains from parameter server.");
665  return false;
666  }
667 
668  if (!this->rosNode->getParam("joint_position_controller/p_gains", this->pos_p_gains))
669  {
670  ROS_ERROR("Could not read position P-gains from parameter server.");
671  return false;
672  }
673 
674  if (!this->rosNode->getParam("joint_position_controller/i_gains", this->pos_i_gains))
675  {
676  ROS_ERROR("Could not read position I-gains from parameter server.");
677  return false;
678  }
679 
680  if (!this->rosNode->getParam("joint_position_controller/d_gains", this->pos_d_gains))
681  {
682  ROS_ERROR("Could not read position D-gains from parameter server.");
683  return false;
684  }
685 
686  if (joint_names.size() != vel_p_gains.size() ||
687  joint_names.size() != vel_i_gains.size() ||
688  joint_names.size() != vel_d_gains.size() ||
689  joint_names.size() != pos_p_gains.size() ||
690  joint_names.size() != pos_i_gains.size() ||
691  joint_names.size() != pos_d_gains.size())
692  {
693  ROS_ERROR("Mismatch in number of joints and number of gains.");
694  return false;
695  }
696 
697  return true;
698 }
699 
700 // Initialize Joint Controllers
702 {
703  for (size_t i = 0; i < this->joint_names.size(); i++)
704  {
705  this->model->GetJointController()->SetVelocityPID(
706  this->model_name + "::" + this->joint_names[i],
707  common::PID(vel_p_gains[i], vel_i_gains[i], vel_d_gains[i])
708  );
709 
710  this->model->GetJointController()->SetPositionPID(
711  this->model_name + "::" + this->joint_names[i],
712  common::PID(pos_p_gains[i], pos_i_gains[i], pos_d_gains[i])
713  );
714  }
715 }
716 
717 // Initialize joint configuration
719 {
720  this->model->GetJointController()->Reset();
721 
723 
724  for (size_t i = 0; i < this->joint_names.size(); i++)
725  {
726  // Set default position
727  this->model->GetJointController()->SetJointPosition(
728  this->model_name + "::" + this->joint_names[i],
730  );
731 
732  // Set controller position reference
733  this->model->GetJointController()->SetPositionTarget(
734  this->model_name + "::" + this->joint_names[i],
736  );
737  }
738 
739 }
740 bool TetrapodPlugin::ResetSimulation(const std_srvs::Empty::Request &_req,
741  std_srvs::Empty::Response &_res)
742 {
743  this->world->Reset();
744 
745  this->model->GetJointController()->Reset();
746 
748 
749  for (size_t i = 0; i < this->joint_names.size(); i++)
750  {
751  // Reset Torques
752  this->model->GetJointController()->SetForce(
753  this->model_name + "::" + this->joint_names[i],
754  0
755  );
756 
757  // Set default position
758  this->model->GetJointController()->SetJointPosition(
759  this->model_name + "::" + this->joint_names[i],
761  );
762 
763  // Set controller position reference
764  this->model->GetJointController()->SetPositionTarget(
765  this->model_name + "::" + this->joint_names[i],
767  );
768  }
769 
770  return true;
771 }
772 
773 } // namespace gazebo
TetrapodPlugin()
Constructor.
std::vector< double > vel_p_gains
Vector of Velocity P-gains.
std::vector< double > pos_i_gains
Vector of Position I-gains.
void OnForceMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming force message from ROS.
Eigen::Matrix< double, 12, 1 > GetJointVelocities()
Get current joint velocities for the robot.
Eigen::Matrix< double, 12, 1 > GetJointPositions()
Get current joint positions for the robot.
physics::LinkPtr base
Pointer to the body link.
void InitJointConfiguration()
The InitJointConfiguration function is called to initialize the desired joint configuration.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
ros::Publisher genVelPub
ROS Generalized Velocities Publisher.
ros::Publisher basePosePub
ROS Base Pose Publisher.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
std::vector< double > pos_d_gains
Vector of Position D-gains.
ros::Subscriber velSub
ROS Velocity Subscriber.
double GetJointForce(const std::string &_joint_name)
Get currently applied force at a specific joint.
double GetJointPosition(const std::string &_joint_name)
Get current position at a specific joint.
void OnFlJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnFlJointStateMsg function handles an incoming joint state message for the front left leg from RO...
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
The Load function is called by Gazebo when the plugin is inserted into simulation.
void SetJointVelocity(const std::string &_joint_name, const double &_vel)
Set the velocity of the joint.
Eigen::Matrix< double, 6, 1 > GetBasePose()
Get current base pose for the robot.
void PublishQueueThread()
The PublishQueueThread function is a ROS helper function that publish state messages.
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
void ProcessQueueThread()
The ProcessQueueThread function is a ROS helper function that processes messages.
ros::Subscriber forceSub
ROS Force Subscriber.
physics::ModelPtr model
Pointer to the model.
ros::ServiceServer resetSimService
ROS Reset Simulation Service.
std::string model_name
Model name.
ControlMode controlMode
Control mode indicator.
bool LoadParametersRos()
The LoadParametersRos function is called to load conffloatiguration from the parameter server.
void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateMsg function handles an incoming joint state message from ROS.
void OnVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming velocity message from ROS.
void SetJointVelocities(const std::vector< double > &_vel)
Set the velocity of the joints.
void SetJointForce(const std::string &_joint_name, const double &_force)
Apply force at a specific joint.
std::vector< double > vel_i_gains
Vector of Velocity I-gains.
void SetJointPosition(const std::string &_joint_name, const double &_pos)
Set the position of the joint.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
ros::Subscriber jointStateCmdSub
ROS Joint State Subscriber.
double GetJointVelocity(const std::string &_joint_name)
Get current velocity at a specific joint.
Eigen::Matrix< double, 6, 1 > GetBaseTwist()
Get current base twist for the robot.
ros::Publisher baseTwistPub
ROS Base Twist Publisher.
ros::Publisher genCoordPub
ROS Generalized Coordinates Publisher.
virtual ~TetrapodPlugin()
Destructor.
ros::Subscriber posSub
ROS Position Subscriber.
std::vector< double > vel_d_gains
Vector of Velocity D-gains.
ros::Publisher jointStatePub
ROS Joint State Publisher.
std::vector< double > pos_p_gains
Vector of Position P-gains.
std::map< std::string, physics::JointPtr > joints
Pointers to the joints.
void SetJointPositions(const std::vector< double > &_pos)
Set the position of the joints.
void InitJointControllers()
The InitJointControllers function is called to setup joint PID controllers.
std::vector< std::string > joint_names
Vector of joint names.
bool ResetSimulation(const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)
The ResetSimulation function handles an incoming reset simulation service request.
void OnPosMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming velocity message from ROS.
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
physics::WorldPtr world
Pointer to the world.
Eigen::Matrix< double, 12, 1 > GetJointForces()
Get current joint forces for the robot.
std::vector< double > joint_config
Vector of joint configuration.
void InitRos()
The initRos function is called to initialize ROS.
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.
void SetJointForces(const std::vector< double > &_forces)
Apply joint forces.
ros::Publisher jointForcesPub
ROS Joint Forces (Torques) Publisher.
Eigen::Vector3d Vector3d
Definition: kinematics.h:49
static constexpr unsigned int NUMJOINTS
Fixed variable for num joints.
double wrapAngleToPi(const double &_rad)
The wrapAngleToPi function wraps an input angle to the interval [-pi, pi).
Definition: angle_utils.cpp:45
double degToRad(const double &_deg)
The degToRad function converts degrees to radians.
Definition: angle_utils.cpp:33