1#ifndef LEG_CONTORLLER_H
2#define LEG_CONTORLLER_H
4#include <eigen_conversions/eigen_msg.h>
5#include <quad_msgs/GRFArray.h>
6#include <quad_msgs/LegCommand.h>
7#include <quad_msgs/LegCommandArray.h>
8#include <quad_msgs/MotorCommand.h>
9#include <quad_msgs/MultiFootPlanContinuous.h>
10#include <quad_msgs/RobotPlan.h>
11#include <quad_msgs/RobotState.h>
12#include <quad_utils/math_utils.h>
13#include <quad_utils/ros_utils.h>
14#include <robot_driver/hardware_interfaces/spirit_interface.h>
16#include <std_msgs/UInt8.h>
19#include <eigen3/Eigen/Eigen>
20#define MATH_PI 3.141592
41 virtual void setGains(
double kp,
double kd);
48 virtual void setGains(
const std::vector<double> &kp,
49 const std::vector<double> &kd);
58 virtual void setGains(
const std::vector<double> &stance_kp,
59 const std::vector<double> &stance_kd,
60 const std::vector<double> &swing_kp,
61 const std::vector<double> &swing_kd,
62 const std::vector<double> &swing_kp_cart,
63 const std::vector<double> &swing_kd_cart);
71 const ros::Time &t_msg);
77 const quad_msgs::RobotState &robot_state_msg,
78 quad_msgs::LegCommandArray &leg_command_array_msg,
79 quad_msgs::GRFArray &grf_array_msg) = 0;
88 std::shared_ptr<quad_utils::QuadKD>
quadKD_;
92 std::vector<double> stance_kd_;
96 std::vector<double> swing_kd_;
100 std::vector<double> swing_kd_cart_;
Implements an abstract class for leg controllers.
Definition: leg_controller.h:28
std::vector< double > stance_kp_
PD gain when foot is in stance.
Definition: leg_controller.h:91
LegController()
Constructor for LegController.
Definition: leg_controller.cpp:3
const int num_feet_
Number of feet.
Definition: leg_controller.h:85
virtual bool computeLegCommandArray(const quad_msgs::RobotState &robot_state_msg, quad_msgs::LegCommandArray &leg_command_array_msg, quad_msgs::GRFArray &grf_array_msg)=0
Compute the leg command array message.
virtual void setGains(double kp, double kd)
Set the desired proportional and derivative gains for all legs.
Definition: leg_controller.cpp:14
std::shared_ptr< quad_utils::QuadKD > quadKD_
QuadKD class.
Definition: leg_controller.h:88
quad_msgs::RobotPlan::ConstPtr last_local_plan_msg_
Last local plan message.
Definition: leg_controller.h:103
std::vector< double > swing_kp_cart_
PD gain when foot is in swing (Cartesian)
Definition: leg_controller.h:99
bool override_state_machine_
Bool for whether to override the state machine.
Definition: leg_controller.h:109
ros::Time last_local_plan_time_
Time of last local plan message.
Definition: leg_controller.h:106
std::vector< double > swing_kp_
PD gain when foot is in swing.
Definition: leg_controller.h:95
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.
Definition: leg_controller.cpp:8