Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes
gazebo::IOBPlugin Class Reference

#include <IOBPlugin.h>

List of all members.

Classes

class  ErrorTerms
struct  force_sensor_info
struct  imu_sensor_info

Public Member Functions

 IOBPlugin ()
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
virtual ~IOBPlugin ()

Private Types

typedef std::map< std::string,
struct force_sensor_info
forceSensorMap
typedef std::map< std::string,
struct imu_sensor_info
imuSensorMap

Private Member Functions

void DeferredLoad ()
void GetForceTorqueSensorState (const common::Time &_curTime)
void GetIMUState (const common::Time &_curTime)
void GetRobotStates (const common::Time &_curTime)
void LoadPIDGainsFromParameter ()
void PublishJointState ()
void RosQueueThread ()
bool serviceCallback (hrpsys_gazebo_msgs::SyncCommandRequest &req, hrpsys_gazebo_msgs::SyncCommandResponse &res)
bool serviceRefCallback (std_srvs::EmptyRequest &req, std_srvs::EmptyResponse &res)
void SetJointCommand (const JointCommand::ConstPtr &_msg)
void SetJointCommand_impl (const JointCommand &_msg)
void SrvQueueThread ()
void UpdatePID_Velocity_Control (double _dt)
void UpdatePIDControl (double _dt)
void UpdateStates ()
void ZeroJointCommand ()

Static Private Member Functions

static double xmlrpc_value_as_double (XmlRpc::XmlRpcValue &v)
static int xmlrpc_value_as_int (XmlRpc::XmlRpcValue &v)

Private Attributes

boost::thread callbackQueeuThread_msg
boost::thread callbackQueeuThread_srv
std::string controller_name
ros::ServiceServer controlServ
boost::thread deferredLoadThread
int effort_average_cnt
int effort_average_window_size
std::vector< double > effortLimit
std::vector< boost::shared_ptr
< std::vector< double > > > 
effortValQueue
std::vector< ErrorTermserrorTerms
int force_sensor_average_cnt
int force_sensor_average_window_size
std::vector< std::stringforceSensorNames
forceSensorMap forceSensors
std::map< std::string,
boost::shared_ptr< std::vector
< boost::shared_ptr
< geometry_msgs::WrenchStamped > > > > 
forceValQueueMap
std::vector< std::stringimuSensorNames
imuSensorMap imuSensors
double iob_period
JointCommand jointCommand
std::vector< double > jointDampingMax
std::vector< double > jointDampingMin
std::vector< double > jointDampingModel
std::vector< std::stringjointNames
ros::ServiceServer jointrefServ
physics::Joint_V joints
common::Time lastControllerUpdateTime
std::vector< double > lastJointCFMDamping
physics::ModelPtr model
boost::mutex mutex
PubMultiQueue pmq
ros::Publisher pubJointState
PubQueue
< sensor_msgs::JointState >
::Ptr 
pubJointStateQueue
int publish_count
bool publish_joint_state
int publish_joint_state_counter
int publish_joint_state_step
int publish_step
ros::Publisher pubRobotState
PubQueue< RobotState >::Ptr pubRobotStateQueue
boost::condition_variable return_service_cond_
std::string robot_name
RobotState robotState
ros::NodeHandlerosNode
ros::CallbackQueue rosQueue
sdf::ElementPtr sdf
ros::CallbackQueue srvQueue
ros::Subscriber subIOBCommand
boost::mutex uniq_mutex
event::ConnectionPtr updateConnection
bool use_joint_effort
bool use_loose_synchronized
bool use_synchronized_command
bool use_velocity_feedback
boost::condition_variable wait_service_cond_
physics::WorldPtr world

Detailed Description

Definition at line 52 of file IOBPlugin.h.


Member Typedef Documentation

Definition at line 134 of file IOBPlugin.h.

Definition at line 135 of file IOBPlugin.h.


Constructor & Destructor Documentation

Definition at line 14 of file IOBPlugin.cpp.

Definition at line 31 of file IOBPlugin.cpp.


Member Function Documentation

Definition at line 504 of file IOBPlugin.cpp.

void gazebo::IOBPlugin::GetForceTorqueSensorState ( const common::Time &  _curTime) [private]
void gazebo::IOBPlugin::GetIMUState ( const common::Time &  _curTime) [private]
void gazebo::IOBPlugin::GetRobotStates ( const common::Time &  _curTime) [private]

Definition at line 777 of file IOBPlugin.cpp.

void gazebo::IOBPlugin::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Definition at line 34 of file IOBPlugin.cpp.

Definition at line 447 of file IOBPlugin.cpp.

Definition at line 652 of file IOBPlugin.cpp.

Definition at line 1064 of file IOBPlugin.cpp.

bool gazebo::IOBPlugin::serviceCallback ( hrpsys_gazebo_msgs::SyncCommandRequest &  req,
hrpsys_gazebo_msgs::SyncCommandResponse &  res 
) [private]

Definition at line 736 of file IOBPlugin.cpp.

bool gazebo::IOBPlugin::serviceRefCallback ( std_srvs::EmptyRequest &  req,
std_srvs::EmptyResponse &  res 
) [private]

Definition at line 752 of file IOBPlugin.cpp.

void gazebo::IOBPlugin::SetJointCommand ( const JointCommand::ConstPtr &  _msg) [private]

Definition at line 559 of file IOBPlugin.cpp.

void gazebo::IOBPlugin::SetJointCommand_impl ( const JointCommand &  _msg) [private]

Definition at line 562 of file IOBPlugin.cpp.

Definition at line 1072 of file IOBPlugin.cpp.

update pid with feedforward force

Definition at line 924 of file IOBPlugin.cpp.

void gazebo::IOBPlugin::UpdatePIDControl ( double  _dt) [private]

update pid with feedforward force

Definition at line 965 of file IOBPlugin.cpp.

Definition at line 681 of file IOBPlugin.cpp.

static double gazebo::IOBPlugin::xmlrpc_value_as_double ( XmlRpc::XmlRpcValue v) [inline, static, private]

Definition at line 183 of file IOBPlugin.h.

static int gazebo::IOBPlugin::xmlrpc_value_as_int ( XmlRpc::XmlRpcValue v) [inline, static, private]

Definition at line 169 of file IOBPlugin.h.

Definition at line 426 of file IOBPlugin.cpp.


Member Data Documentation

Definition at line 104 of file IOBPlugin.h.

Definition at line 105 of file IOBPlugin.h.

Definition at line 162 of file IOBPlugin.h.

Definition at line 121 of file IOBPlugin.h.

boost::thread gazebo::IOBPlugin::deferredLoadThread [private]

Definition at line 106 of file IOBPlugin.h.

Definition at line 202 of file IOBPlugin.h.

Definition at line 203 of file IOBPlugin.h.

std::vector<double> gazebo::IOBPlugin::effortLimit [private]

Definition at line 141 of file IOBPlugin.h.

std::vector< boost::shared_ptr<std::vector<double> > > gazebo::IOBPlugin::effortValQueue [private]

Definition at line 204 of file IOBPlugin.h.

std::vector<ErrorTerms> gazebo::IOBPlugin::errorTerms [private]

Definition at line 151 of file IOBPlugin.h.

Definition at line 199 of file IOBPlugin.h.

Definition at line 198 of file IOBPlugin.h.

Definition at line 136 of file IOBPlugin.h.

Definition at line 138 of file IOBPlugin.h.

std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<geometry_msgs::WrenchStamped> > > > gazebo::IOBPlugin::forceValQueueMap [private]

Definition at line 200 of file IOBPlugin.h.

Definition at line 137 of file IOBPlugin.h.

Definition at line 139 of file IOBPlugin.h.

Definition at line 167 of file IOBPlugin.h.

JointCommand gazebo::IOBPlugin::jointCommand [private]

Definition at line 123 of file IOBPlugin.h.

std::vector<double> gazebo::IOBPlugin::jointDampingMax [private]

Definition at line 131 of file IOBPlugin.h.

std::vector<double> gazebo::IOBPlugin::jointDampingMin [private]

Definition at line 132 of file IOBPlugin.h.

std::vector<double> gazebo::IOBPlugin::jointDampingModel [private]

Definition at line 130 of file IOBPlugin.h.

Definition at line 126 of file IOBPlugin.h.

Definition at line 120 of file IOBPlugin.h.

physics::Joint_V gazebo::IOBPlugin::joints [private]

Definition at line 127 of file IOBPlugin.h.

Definition at line 108 of file IOBPlugin.h.

std::vector<double> gazebo::IOBPlugin::lastJointCFMDamping [private]

Definition at line 129 of file IOBPlugin.h.

physics::ModelPtr gazebo::IOBPlugin::model [private]

Definition at line 99 of file IOBPlugin.h.

boost::mutex gazebo::IOBPlugin::mutex [private]

Definition at line 155 of file IOBPlugin.h.

Definition at line 154 of file IOBPlugin.h.

Definition at line 117 of file IOBPlugin.h.

PubQueue<sensor_msgs::JointState>::Ptr gazebo::IOBPlugin::pubJointStateQueue [private]

Definition at line 118 of file IOBPlugin.h.

Definition at line 206 of file IOBPlugin.h.

Definition at line 114 of file IOBPlugin.h.

Definition at line 116 of file IOBPlugin.h.

Definition at line 115 of file IOBPlugin.h.

Definition at line 207 of file IOBPlugin.h.

Definition at line 111 of file IOBPlugin.h.

PubQueue<RobotState>::Ptr gazebo::IOBPlugin::pubRobotStateQueue [private]

Definition at line 112 of file IOBPlugin.h.

boost::condition_variable gazebo::IOBPlugin::return_service_cond_ [private]

Definition at line 159 of file IOBPlugin.h.

Definition at line 161 of file IOBPlugin.h.

RobotState gazebo::IOBPlugin::robotState [private]

Definition at line 110 of file IOBPlugin.h.

Definition at line 94 of file IOBPlugin.h.

Definition at line 95 of file IOBPlugin.h.

sdf::ElementPtr gazebo::IOBPlugin::sdf [private]

Definition at line 100 of file IOBPlugin.h.

Definition at line 96 of file IOBPlugin.h.

Definition at line 124 of file IOBPlugin.h.

boost::mutex gazebo::IOBPlugin::uniq_mutex [private]

Definition at line 157 of file IOBPlugin.h.

Definition at line 102 of file IOBPlugin.h.

Definition at line 166 of file IOBPlugin.h.

Definition at line 164 of file IOBPlugin.h.

Definition at line 163 of file IOBPlugin.h.

Definition at line 165 of file IOBPlugin.h.

boost::condition_variable gazebo::IOBPlugin::wait_service_cond_ [private]

Definition at line 158 of file IOBPlugin.h.

Definition at line 98 of file IOBPlugin.h.


The documentation for this class was generated from the following files:


hrpsys_gazebo_general
Author(s): Yohei Kakiuchi , Kei Okada , Masaki Murooka
autogenerated on Thu Jun 6 2019 20:56:54