The modelplugin that actually controls the model and provide low level apis.  
 More...
#include <ModuleController.hh>
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. 
 
      
        
          | 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_point | Coordinates of the Start point  | 
    | end_point | Coordinates 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_value | The value need to be filtered  | 
    | complement_filter_par | Complementry filter factor, defined in the following equation: complement_filter_par*value_history + (1 - complement_filter_par) filtering_value  | 
    | *value_history | The 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_value | The value need to be filtered  | 
    | *value_history | The 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_joint | Current joint intersted  | 
    | rot_axis | Axis 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
 - 
  
  
 
- Returns
 - Index of the corresponding axis 
 
 
 
      
        
          | SmoresJoint & gazebo::ModuleController::GetJointPlus  | 
          ( | 
          int  | 
          node_ID | ) | 
           | 
        
      
 
Returns the SmoresJoint structure according to the node ID. 
- Parameters
 - 
  
  
 
- 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
 - 
  
    | joint | Joint object pointer whose revolution rate needs to be calculate  | 
    | axis_index | Index of the axis, for a single joint type, it is always 0  | 
  
   
- Returns
 - Joint speed in rad/s 
 
 
 
      
        
          | 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: