30 #include <gazebo/gazebo.hh>
31 #include <gazebo/physics/physics.hh>
32 #include <gazebo/transport/transport.hh>
33 #include <gazebo/msgs/msgs.hh>
38 #include "ros/package.h"
39 #include "ros/console.h"
40 #include "ros/callback_queue.h"
41 #include "ros/subscribe_options.h"
42 #include "eigen_conversions/eigen_msg.h"
43 #include "std_msgs/Float32.h"
44 #include "std_msgs/Float64MultiArray.h"
45 #include "sensor_msgs/JointState.h"
46 #include "std_srvs/Empty.h"
82 public:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
125 public:
void SetJointForce(
const std::string &_joint_name,
const double &_force);
134 public:
void SetJointVelocity(
const std::string &_joint_name,
const double &_vel);
151 public:
void OnJointStateMsg(
const sensor_msgs::JointStateConstPtr &_msg);
157 public:
void OnForceMsg(
const std_msgs::Float64MultiArrayConstPtr &_msg);
163 public:
void OnVelMsg(
const std_msgs::Float64MultiArrayConstPtr &_msg);
169 public:
void OnPosMsg(
const std_msgs::Float64MultiArrayConstPtr &_msg);
180 public:
void printMap(
const std::map<std::string,physics::JointPtr> &_map);
208 std_srvs::Empty::Response &_res);
220 private: physics::LinkPtr
base;
225 private: std::map<std::string, physics::JointPtr>
joints;
256 private: std::unique_ptr<ros::NodeHandle>
rosNode;
A plugin to control the single_leg robot.
void OnForceMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming force message from ROS.
void ProcessQueueThread()
The ProcessQueueThread function is a ROS helper function that processes messages.
std::thread rosProcessQueueThread
Thread running the rosProcessQueue.
ros::Subscriber posSub
ROS Position Subscriber.
void SetJointPositions(const std::vector< double > &_pos)
Set the position of the joints.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
The Load function is called by Gazebo when the plugin is inserted into simulation.
virtual ~SingleLegPlugin()
Destructor.
double GetJointPosition(const std::string &_joint_name)
Get current position at a specific joint.
ros::Subscriber forceSub
ROS Force Subscriber.
Eigen::Matrix< double, 6, 1 > GetBaseTwist()
Get current base twist for the robot.
Eigen::Matrix< double, 6, 1 > GetBasePose()
Get current base pose for the robot.
bool LoadParametersRos()
The LoadParametersRos function is called to load conffloatiguration from the parameter server.
std::vector< double > vel_i_gains
Vector of Velocity I-gains.
double GetJointVelocity(const std::string &_joint_name)
Get current velocity at a specific joint.
std::vector< double > joint_config
Vector of joint configuration.
ros::Publisher genCoordPub
ROS Generalized Coordinates Publisher.
void SetJointForce(const std::string &_joint_name, const double &_force)
Apply force at a specific joint.
void OnJointStateMsg(const sensor_msgs::JointStateConstPtr &_msg)
The OnJointStateMsg function handles an incoming joint state message from ROS.
Eigen::Matrix< double, 3, 1 > GetJointPositions()
Get current joint positions for the robot.
std::string model_name
Model name.
SingleLegPlugin()
Constructor.
ros::Publisher jointForcesPub
ROS Joint Forces (Torques) Publisher.
void InitRos()
The initRos function is called to initialize ROS.
physics::LinkPtr base
Pointer to the body link.
std::unique_ptr< ros::NodeHandle > rosNode
Node used for ROS transport.
std::vector< double > vel_p_gains
Vector of Velocity P-gains.
std::map< std::string, physics::JointPtr > joints
Pointers to the joints.
void PublishQueueThread()
The PublishQueueThread function is a ROS helper function that publish state messages.
std::vector< double > pos_i_gains
Vector of Position I-gains.
Eigen::Matrix< double, 3, 1 > GetJointVelocities()
Get current joint velocities for the robot.
physics::WorldPtr world
Pointer to the world.
ControlMode controlMode
Control mode indicator { position = 1, velocity = 2, torque = 3 }.
void InitJointConfiguration()
The InitJointConfiguration function is called to initialize the desired joint configuration.
void SetJointForces(const std::vector< double > &_forces)
Apply joint forces.
bool ResetSimulation(const std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res)
The ResetSimulation function handles an incoming reset simulation service request.
ros::ServiceServer resetSimService
ROS Reset Simulation Service.
void OnPosMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming velocity message from ROS.
void InitRosQueueThreads()
The InitRosQueueThreads function is called to initialize the ROS Publish and Process Queue Threads.
ros::Subscriber jointStateSub
ROS Joint State Subscriber.
Eigen::Matrix< double, 3, 1 > GetJointForces()
Get current joint forces for the robot.
ros::Publisher genVelPub
ROS Generalized Velocities Publisher.
std::vector< std::string > joint_names
Vector of joint names.
double GetJointForce(const std::string &_joint_name)
Get currently applied force at a specific joint.
void InitJointControllers()
The InitJointControllers function is called to setup joint PID controllers.
ros::CallbackQueue rosPublishQueue
ROS callbackque that helps publish messages.
std::vector< double > vel_d_gains
Vector of Velocity D-gains.
ros::CallbackQueue rosProcessQueue
ROS callbackque that helps process messages.
ros::Subscriber velSub
ROS Velocity Subscriber.
void SetJointVelocity(const std::string &_joint_name, const double &_vel)
Set the velocity of the joint.
std::thread rosPublishQueueThread
Thread running the rosPublishQueue.
std::vector< double > pos_d_gains
Vector of Position D-gains.
physics::ModelPtr model
Pointer to the model.
void printMap(const std::map< std::string, physics::JointPtr > &_map)
std::vector< double > pos_p_gains
Vector of Position P-gains.
void SetJointVelocities(const std::vector< double > &_vel)
Set the velocity of the joints.
void OnVelMsg(const std_msgs::Float64MultiArrayConstPtr &_msg)
The OnRosMsg function handles an incoming velocity message from ROS.
Eigen::Matrix< double, 3, 1 > JointVelocities
static constexpr unsigned int NUMJOINTS
Fixed variable for num joints.