Quad-SDK
Loading...
Searching...
No Matches
joint_controller.h
1#ifndef JOINT_CONTROLLER_H
2#define JOINT_CONTROLLER_H
3
4#include <geometry_msgs/Vector3.h>
5#include <robot_driver/controllers/leg_controller.h>
6
8
14 public:
20
21 void updateSingleJointCommand(const geometry_msgs::Vector3::ConstPtr &msg);
22
30 bool computeLegCommandArray(const quad_msgs::RobotState &robot_state_msg,
31 quad_msgs::LegCommandArray &leg_command_array_msg,
32 quad_msgs::GRFArray &grf_array_msg);
33
34 private:
36 int leg_idx_ = 0;
37
39 int joint_idx_ = 0;
40
42 double joint_torque_ = 0.0;
43};
44
45#endif // JOINT_CONTROLLER_H
Implements inverse dynamics as a controller within the ROS framework.
Definition joint_controller.h:13
double joint_torque_
Desired torque in Nm.
Definition joint_controller.h:42
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.
Definition joint_controller.cpp:17
int joint_idx_
Joint index for controlled joint.
Definition joint_controller.h:39
JointController()
Constructor for JointController.
Definition joint_controller.cpp:3
int leg_idx_
Leg index for controlled joint.
Definition joint_controller.h:36
Implements an abstract class for leg controllers.
Definition leg_controller.h:28