57 this->
world = _model->GetWorld();
64 this->
base = _model->GetLink(this->
model_name +
"::tetrapod::body");
67 this->
joints = this->
model->GetJointController()->GetJoints();
72 ROS_INFO_STREAM(
t.first);
81 ROS_ERROR(
"Could not load parameters.");
98 ignition::math::Pose3d base_pose = this->
base->WorldPose();
100 Eigen::Matrix<double, 6, 1> q_b;
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();
119 Eigen::Matrix<double, 6, 1> u_b;
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();
137 double force = this->
joints[this->
model_name +
"::" + _joint_name]->GetForce(0);
148 Eigen::Matrix<double, 12, 1> tau_r;
176 double vel = this->
joints[this->
model_name +
"::" + _joint_name]->GetVelocity(0);
184 Eigen::Matrix<double, 12, 1> dot_q_r;
212 double pos = this->
joints[this->
model_name +
"::" + _joint_name]->Position();
220 Eigen::Matrix<double, 12, 1> q_r;
249 this->
model->GetJointController()->SetForce(
258 auto start = std::chrono::steady_clock::now();
262 this->
model->GetJointController()->Reset();
267 for (
size_t i = 0; i < this->
joint_names.size(); i++)
269 this->
model->GetJointController()->SetForce(
275 auto end = std::chrono::steady_clock::now();
277 std::chrono::duration<double,std::micro> diff = end - start;
279 ROS_DEBUG_STREAM(
"Time spent resetting commands and applying torques: " << diff.count() <<
" microseconds.");
285 this->
model->GetJointController()->SetVelocityTarget(
294 auto start = std::chrono::steady_clock::now();
298 this->
model->GetJointController()->Reset();
303 for (
size_t i = 0; i < this->
joint_names.size(); i++)
305 this->
model->GetJointController()->SetVelocityTarget(
311 auto end = std::chrono::steady_clock::now();
313 std::chrono::duration<double,std::micro> diff = end - start;
315 ROS_DEBUG_STREAM(
"Time spent resetting commands and setting velocity targets: " << diff.count() <<
" microseconds.");
321 this->
model->GetJointController()->SetPositionTarget(
330 auto start = std::chrono::steady_clock::now();
334 this->
model->GetJointController()->Reset();
339 for (
size_t i = 0; i < this->
joint_names.size(); i++)
341 this->
model->GetJointController()->SetPositionTarget(
347 auto end = std::chrono::steady_clock::now();
349 std::chrono::duration<double,std::micro> diff = end - start;
351 ROS_DEBUG_STREAM(
"Time spent resetting commands and setting position targets: " << diff.count() <<
" microseconds.");
357 if ((!_msg->position.empty()) && (_msg->position.size() ==
NUMJOINTS))
362 if ((!_msg->velocity.empty()) && (_msg->velocity.size() ==
NUMJOINTS))
367 if ((!_msg->effort.empty()) && (_msg->effort.size() ==
NUMJOINTS))
376 if ((!_msg->position.empty()) && (_msg->position.size() == 3))
383 if ((!_msg->velocity.empty()) && (_msg->velocity.size() == 3))
390 if ((!_msg->effort.empty()) && (_msg->effort.size() == 3))
419 static const double timeout = 0.000001;
429 ros::Rate loop_rate(200);
432 Eigen::Matrix<double, 18, 1> q;
433 Eigen::Matrix<double, 18, 1> u;
434 Eigen::Matrix<double, 12, 1> tau;
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;
451 tf::matrixEigenToMsg(q, gen_coord_msg);
452 tf::matrixEigenToMsg(u, gen_vel_msg);
453 tf::matrixEigenToMsg(tau, joint_forces_msg);
455 tf::matrixEigenToMsg(q.topRows(6), base_pose_msg);
456 tf::matrixEigenToMsg(u.topRows(6), base_twist_msg);
458 joint_state_msg.header.stamp = ros::Time::now();
459 for(
int i = 0; i < 12; i++)
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));
480 if (!ros::isInitialized())
488 ros::init_options::NoSigintHandler
492 this->
rosNode.reset(
new ros::NodeHandle(
"gazebo_client"));
494 ros::AdvertiseServiceOptions reset_simulation_aso =
495 ros::AdvertiseServiceOptions::create<std_srvs::Empty>(
496 "/" + this->
model->GetName() +
"/reset_simulation",
499 &this->rosProcessQueue
502 ros::AdvertiseOptions gen_coord_ao =
503 ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
504 "/" + this->
model->GetName() +
"/gen_coord",
506 ros::SubscriberStatusCallback(),
507 ros::SubscriberStatusCallback(),
509 &this->rosPublishQueue
512 ros::AdvertiseOptions gen_vel_ao =
513 ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
514 "/" + this->
model->GetName() +
"/gen_vel",
516 ros::SubscriberStatusCallback(),
517 ros::SubscriberStatusCallback(),
519 &this->rosPublishQueue
522 ros::AdvertiseOptions base_pose_so =
523 ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
524 "/" + this->
model->GetName() +
"/base_pose",
526 ros::SubscriberStatusCallback(),
527 ros::SubscriberStatusCallback(),
529 &this->rosPublishQueue
532 ros::AdvertiseOptions base_twist_so =
533 ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
534 "/" + this->
model->GetName() +
"/base_twist",
536 ros::SubscriberStatusCallback(),
537 ros::SubscriberStatusCallback(),
539 &this->rosPublishQueue
542 ros::AdvertiseOptions joint_forces_ao =
543 ros::AdvertiseOptions::create<std_msgs::Float64MultiArray>(
544 "/" + this->
model->GetName() +
"/joint_forces",
546 ros::SubscriberStatusCallback(),
547 ros::SubscriberStatusCallback(),
549 &this->rosPublishQueue
552 ros::AdvertiseOptions joint_state_ao =
553 ros::AdvertiseOptions::create<sensor_msgs::JointState>
555 "/" + this->
model->GetName() +
"/joint_state",
557 ros::SubscriberStatusCallback(),
558 ros::SubscriberStatusCallback(),
560 &this->rosPublishQueue
563 ros::SubscribeOptions joint_state_cmd_so =
564 ros::SubscribeOptions::create<sensor_msgs::JointState>(
565 "/" + this->
model->GetName() +
"/joint_state_cmd",
569 &this->rosProcessQueue
572 ros::SubscribeOptions force_so =
573 ros::SubscribeOptions::create<std_msgs::Float64MultiArray>(
574 "/" + this->
model->GetName() +
"/force_cmd",
578 &this->rosProcessQueue
581 ros::SubscribeOptions vel_so =
582 ros::SubscribeOptions::create<std_msgs::Float64MultiArray>(
583 "/" + this->
model->GetName() +
"/vel_cmd",
587 &this->rosProcessQueue
590 ros::SubscribeOptions pos_so =
591 ros::SubscribeOptions::create<std_msgs::Float64MultiArray>(
592 "/" + this->
model->GetName() +
"/pos_cmd",
596 &this->rosProcessQueue
638 if (!this->
rosNode->getParam(
"joint_names", this->joint_names))
640 ROS_ERROR(
"Could not read joint names from parameter server.");
644 if (!this->
rosNode->getParam(
"joint_config", this->joint_config))
646 ROS_ERROR(
"Could not read joint config from parameter server.");
650 if (!this->
rosNode->getParam(
"joint_velocity_controller/p_gains", this->vel_p_gains))
652 ROS_ERROR(
"Could not read velocity P-gains from parameter server.");
656 if (!this->
rosNode->getParam(
"joint_velocity_controller/i_gains", this->vel_i_gains))
658 ROS_ERROR(
"Could not read velocity I-gains from parameter server.");
662 if (!this->
rosNode->getParam(
"joint_velocity_controller/d_gains", this->vel_d_gains))
664 ROS_ERROR(
"Could not read velocity D-gains from parameter server.");
668 if (!this->
rosNode->getParam(
"joint_position_controller/p_gains", this->pos_p_gains))
670 ROS_ERROR(
"Could not read position P-gains from parameter server.");
674 if (!this->
rosNode->getParam(
"joint_position_controller/i_gains", this->pos_i_gains))
676 ROS_ERROR(
"Could not read position I-gains from parameter server.");
680 if (!this->
rosNode->getParam(
"joint_position_controller/d_gains", this->pos_d_gains))
682 ROS_ERROR(
"Could not read position D-gains from parameter server.");
693 ROS_ERROR(
"Mismatch in number of joints and number of gains.");
703 for (
size_t i = 0; i < this->
joint_names.size(); i++)
705 this->
model->GetJointController()->SetVelocityPID(
710 this->
model->GetJointController()->SetPositionPID(
720 this->
model->GetJointController()->Reset();
724 for (
size_t i = 0; i < this->
joint_names.size(); i++)
727 this->
model->GetJointController()->SetJointPosition(
733 this->
model->GetJointController()->SetPositionTarget(
741 std_srvs::Empty::Response &_res)
743 this->
world->Reset();
745 this->
model->GetJointController()->Reset();
749 for (
size_t i = 0; i < this->
joint_names.size(); i++)
752 this->
model->GetJointController()->SetForce(
758 this->
model->GetJointController()->SetJointPosition(
764 this->
model->GetJointController()->SetPositionTarget(
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.
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).
double degToRad(const double &_deg)
The degToRad function converts degrees to radians.