|
Quad-SDK
|
Implements inverse dynamics as a controller within the ROS framework. More...
#include <joint_controller.h>


Public Member Functions | |
| JointController () | |
| Constructor for JointController. | |
| void | updateSingleJointCommand (const geometry_msgs::Vector3::ConstPtr &msg) |
| bool | computeLegCommandArray (const quad_msgs::RobotState &robot_state_msg, quad_msgs::LegCommandArray &leg_command_array_msg, quad_msgs::GRFArray &grf_array_msg) |
| Compute the leg command array message for a given current state and reference plan. | |
Public Member Functions inherited from LegController | |
| LegController () | |
| Constructor for LegController. | |
| virtual void | init (double kp, double kd) |
| Set the desired proportional and derivative gains for all legs. | |
| virtual void | init (const std::vector< double > &kp, const std::vector< double > &kd) |
| Set the desired proportional and derivative gains for each leg. | |
| virtual void | init (const std::vector< double > &stance_kp, const std::vector< double > &stance_kd, const std::vector< double > &swing_kp, const std::vector< double > &swing_kd, const std::vector< double > &swing_kp_cart, const std::vector< double > &swing_kd_cart) |
| Set the desired stance and swing proportional and derivative gains. | |
| void | updateLocalPlanMsg (quad_msgs::RobotPlan::ConstPtr msg, const ros::Time &t_msg) |
| Compute the leg command array message for a given current state and reference plan. | |
| bool | overrideStateMachine () |
Private Attributes | |
| int | leg_idx_ = 0 |
| Leg index for controlled joint. | |
| int | joint_idx_ = 0 |
| Joint index for controlled joint. | |
| double | joint_torque_ = 0.0 |
| Desired torque in Nm. | |
Additional Inherited Members | |
Protected Attributes inherited from LegController | |
| const int | num_feet_ = 4 |
| Number of feet. | |
| std::shared_ptr< quad_utils::QuadKD > | quadKD_ |
| QuadKD class. | |
| std::vector< double > | stance_kp_ |
| PD gain when foot is in stance. | |
| std::vector< double > | stance_kd_ |
| std::vector< double > | swing_kp_ |
| PD gain when foot is in swing. | |
| std::vector< double > | swing_kd_ |
| std::vector< double > | swing_kp_cart_ |
| PD gain when foot is in swing (Cartesian) | |
| std::vector< double > | swing_kd_cart_ |
| quad_msgs::RobotPlan::ConstPtr | last_local_plan_msg_ |
| Last local plan message. | |
| ros::Time | last_local_plan_time_ |
| Time of last local plan message. | |
| bool | override_state_machine_ |
| Bool for whether to override the state machine. | |
Implements inverse dynamics as a controller within the ROS framework.
JointController implements inverse dynamics logic. It should expose a constructor that does any initialization required and an update method called at some frequency.
| JointController::JointController | ( | ) |
Constructor for JointController.
|
virtual |
Compute the leg command array message for a given current state and reference plan.
| [out] | leg_command_array_msg | Command message after solving inverse dynamics and including reference setpoints for each joint |
| [out] | grf_array_msg | GRF command message |
Implements LegController.