Quad-SDK
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
effort_controllers::QuadController Class Reference

Forward command controller for quad. More...

#include <controller_plugin.h>

Inheritance diagram for effort_controllers::QuadController:
Inheritance graph
[legend]
Collaboration diagram for effort_controllers::QuadController:
Collaboration graph
[legend]

Public Member Functions

 QuadController ()
 Forward command controller for a set of effort controlled joints (torque or force).
 
bool init (hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n)
 
void update (const ros::Time &, const ros::Duration &)
 

Public Attributes

std::vector< std::string > joint_names_
 
std::vector< hardware_interface::JointHandle > joints_
 
realtime_tools::RealtimeBuffer< BufferType > commands_buffer_
 
unsigned int n_joints_
 

Private Types

typedef std::vector< quad_msgs::LegCommand > BufferType
 

Private Member Functions

void commandCB (const quad_msgs::LegCommandArrayConstPtr &msg)
 
void enforceJointLimits (double &command, unsigned int index)
 

Private Attributes

ros::Subscriber sub_command_
 Subscriber for new LegCommandArray messages.
 
std::vector< urdf::JointConstSharedPtr > joint_urdfs_
 Store reference to gazebo joints.
 
std::map< int, std::pair< int, int > > leg_map_
 Map gazebo/urdf joint indices to leg/joint pair.
 
std::vector< double > torque_lims_
 Torque limits for each motor.
 
std::vector< double > speed_lims_
 

Detailed Description

Forward command controller for quad.

This class forwards the commanded efforts down to a set of joints.

Constructor & Destructor Documentation

◆ QuadController()

effort_controllers::QuadController::QuadController ( )

Forward command controller for a set of effort controlled joints (torque or force).

This class forwards the commanded efforts down to a set of joints.

interface

Parameters
typeMust be "JointGroupEffortController".
jointsList of names of the joints to control.

Subscribes to:

  • command (std_msgs::Float64MultiArray) : The joint efforts to apply

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