SMORES Robot Platform Simulation
Modlab at Penn, ASL at Cornell
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends
gazebo::ModuleController Class Reference

The modelplugin that actually controls the model and provide low level apis. More...

#include <ModuleController.hh>

Inheritance diagram for gazebo::ModuleController:

Public Member Functions

 ModuleController ()
 Constructor.
 
 ~ModuleController ()
 Destructor.
 
double RevolutionSpeedCal (physics::JointPtr joint, const int axis_index)
 Calculates the angular velocity of a revolute joint. More...
 
math::Pose GetModelCentralCoor (void)
 Gets the coordinates and direction of the current model. More...
 
math::Angle AngleCalculation2Points (math::Vector2d start_point, math::Vector2d end_point)
 Calculates the anlge of the line connected two points in the world frame. More...
 
double ComplementaryFilter (double filtering_value, double complement_filter_par, double *value_history)
 Apply a complementary filter a raw sensor value. More...
 
double ComplementaryFilter (double filtering_value, double *value_history)
 Applies a complementary filter with a default factor of 0.9. More...
 
SmoresJointGetJointPlus (int node_ID)
 Returns the SmoresJoint structure according to the node ID. More...
 
int GetJointAxis (int node_ID)
 Returns the index of joint axis according to the node ID. More...
 
math::Angle GetJointAngle (physics::JointPtr current_joint, int rot_axis)
 Returns the angle of the specified joint. More...
 

Public Attributes

physics::ModelPtr model
 Current Model Pointer.
 
transport::PublisherPtr collisionInfoToServer
 Publisher of the collision information.
 
math::Vector3 jointAngleKPID
 Default Joint Angle PID controller parameter. More...
 
math::Vector3 modelAngleKPID
 Default Joint Angle PID controller parameter. More...
 
double maxiRotationRate
 Maximium rotation rate of each joint, unit: rad/s.
 
double accelerationRate
 Acceleration rate of the planar motion.
 
double planarMotionStopThreshold
 Planar motion control threshold.
 
double wheelRadius
 Radius of the wheels.
 

Detailed Description

The modelplugin that actually controls the model and provide low level apis.

This class is a gazebo modelplugin. All the low level controllers of SMORES robot are defined here.

Member Function Documentation

math::Angle gazebo::ModuleController::AngleCalculation2Points ( math::Vector2d  start_point,
math::Vector2d  end_point 
)

Calculates the anlge of the line connected two points in the world frame.

Parameters
start_pointCoordinates of the Start point
end_pointCoordinates of the End point
Returns
Angle between 2 points in rad in the global frame math::Angle object
double gazebo::ModuleController::ComplementaryFilter ( double  filtering_value,
double  complement_filter_par,
double *  value_history 
)

Apply a complementary filter a raw sensor value.

Parameters
filtering_valueThe value need to be filtered
complement_filter_parComplementry filter factor, defined in the following equation: complement_filter_par*value_history + (1 - complement_filter_par) filtering_value
*value_historyThe pointer points to the prrior filtering value. /return The filered value
double gazebo::ModuleController::ComplementaryFilter ( double  filtering_value,
double *  value_history 
)

Applies a complementary filter with a default factor of 0.9.

Parameters
filtering_valueThe value need to be filtered
*value_historyThe pointer points to the prrior filtering value. /return The result the filered value
math::Angle gazebo::ModuleController::GetJointAngle ( physics::JointPtr  current_joint,
int  rot_axis 
)

Returns the angle of the specified joint.

Parameters
current_jointCurrent joint intersted
rot_axisAxis rotated along
Returns
Joint angle position in a math::Angle object
int gazebo::ModuleController::GetJointAxis ( int  node_ID)

Returns the index of joint axis according to the node ID.

Parameters
node_IDID of node
Returns
Index of the corresponding axis
SmoresJoint & gazebo::ModuleController::GetJointPlus ( int  node_ID)

Returns the SmoresJoint structure according to the node ID.

Parameters
node_IDID of node
Returns
Corresponding SmoresJoint object
math::Pose gazebo::ModuleController::GetModelCentralCoor ( void  )

Gets the coordinates and direction of the current model.

Returns
The global coordinates of the current model, which is a math::Pose object
double gazebo::ModuleController::RevolutionSpeedCal ( physics::JointPtr  joint,
const int  axis_index 
)

Calculates the angular velocity of a revolute joint.

Parameters
jointJoint object pointer whose revolution rate needs to be calculate
axis_indexIndex of the axis, for a single joint type, it is always 0
Returns
Joint speed in rad/s

Member Data Documentation

math::Vector3 gazebo::ModuleController::jointAngleKPID

Default Joint Angle PID controller parameter.

First digit is Kp, Second digit is Ki and Third digit is Kd

math::Vector3 gazebo::ModuleController::modelAngleKPID

Default Joint Angle PID controller parameter.

First digit is Kp, Second digit is Ki and Third digit is Kd


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