|
| GaitController (int controller_freq, double gait_period, std::function< Eigen::Vector3d(double)> fl_traj, std::function< Eigen::Vector3d(double)> fr_traj, std::function< Eigen::Vector3d(double)> rl_traj, std::function< Eigen::Vector3d(double)> rr_traj) |
|
void | increment () |
|
void | UpdateFeetReferences () |
|
| Controller (int controller_freq) |
|
virtual | ~Controller () |
|
bool | RunStandUpSequence () |
|
void | waitForReadyToProceed () |
|
bool | UpdateJointCommands () |
|
bool | UpdateVelocityCommands () |
|
bool | sendJointPositionCommands () |
|
void | StandStill (const double &duration) |
|
virtual void | setInitialConfiguration () |
|
void | SetTwistCommand (double lin_vel_cmd_x, double lin_vel_cmd_y, double ang_vel_cmd_z) |
|
void | initROS () |
|
void | WaitForInitialState () |
|
bool | MoveFeetToPositions (Eigen::Matrix< double, 3, 1 > fl_goal_foot_pos, Eigen::Matrix< double, 3, 1 > fr_goal_foot_pos, Eigen::Matrix< double, 3, 1 > rl_goal_foot_pos, Eigen::Matrix< double, 3, 1 > rr_goal_foot_pos) |
|
bool | MoveJointsToSetpoints (Eigen::Matrix< double, 12, 1 > goal_joint_angles) |
|
bool | MoveFootToPosition (const Kinematics::LegType &leg_type, const Eigen::Matrix< double, 3, 1 > &goal_foot_position) |
|
void | UpdateFeetPositions () |
|
bool | CheckReadyToProceed () |
|
void | ResetReadyToProceedFlag () |
|
void | SetReadyToProceedFlag () |
|
bool | ReadyToProceed (std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res) |
| The ReadyToProceed function handles an incoming readyToProceed service request. More...
|
|
bool | Shutdown (std_srvs::Empty::Request &_req, std_srvs::Empty::Response &_res) |
| The Shutdown function handles an incoming shutdown service request. More...
|
|
void | WriteToLog () |
|
|
using | JointState = Eigen::Matrix< double, 12, 1 > |
|
void | jointStateCallback (const sensor_msgs::JointStatePtr &msg) |
|
void | readyToProceedCallback (const std_msgs::Bool &msg) |
|
void | TwistCommandCallback (const geometry_msgs::TwistConstPtr &_msg) |
| Converts twist command messages into desired linear and angular body velocities. More...
|
|
void | TwistStateCallback (const geometry_msgs::TwistConstPtr &_msg) |
|
void | BasePoseStateCallback (const std_msgs::Float64MultiArrayConstPtr &msg) |
|
std::string | node_name = "controller_node" |
|
std::string | robot_name = ROBOT_NAME |
|
int | controller_freq |
|
Kinematics | kinematics |
|
ros::NodeHandlePtr | nodeHandle |
|
ros::Publisher | joint_command_publisher |
|
ros::Subscriber | joint_state_subscriber |
|
ros::Subscriber | base_pose_state_subscriber |
|
ros::Subscriber | ready_to_proceed_subscriber |
|
ros::Subscriber | twist_command_subscriber |
| Subscribes to twist command messages from an external controller. More...
|
|
ros::Subscriber | twist_state_subscriber |
|
Eigen::Vector3d | fl_offset = Eigen::Vector3d(LEG_OFFSET_LENGTH, LEG_OFFSET_LENGTH, 0) |
|
Eigen::Vector3d | fr_offset = Eigen::Vector3d(LEG_OFFSET_LENGTH, -LEG_OFFSET_LENGTH, 0) |
|
Eigen::Vector3d | rl_offset = Eigen::Vector3d(-LEG_OFFSET_LENGTH, LEG_OFFSET_LENGTH, 0) |
|
Eigen::Vector3d | rr_offset = Eigen::Vector3d(-LEG_OFFSET_LENGTH, -LEG_OFFSET_LENGTH, 0) |
|
Eigen::Vector3d | fl_position_body |
|
Eigen::Vector3d | fr_position_body |
|
Eigen::Vector3d | rl_position_body |
|
Eigen::Vector3d | rr_position_body |
|
Eigen::Vector3d | fl_velocity_body |
|
Eigen::Vector3d | fr_velocity_body |
|
Eigen::Vector3d | rl_velocity_body |
|
Eigen::Vector3d | rr_velocity_body |
|
Eigen::Vector3d | fl_acceleration_body |
|
Eigen::Vector3d | fr_acceleration_body |
|
Eigen::Vector3d | rl_acceleration_body |
|
Eigen::Vector3d | rr_acceleration_body |
|
JointState | joint_angle_commands = JointState::Zero() |
|
JointState | joint_velocity_commands = JointState::Zero() |
|
JointState | joint_acceleration_commands = JointState::Zero() |
|
JointState | joint_torque_commands = JointState::Zero() |
|
JointState | joint_angles = JointState::Constant(UNINITIALIZED_JOINT_STATE) |
|
JointState | joint_velocities = JointState::Zero() |
|
JointState | joint_torques = JointState::Zero() |
|
Eigen::Matrix< double, 6, 1 > | base_pose_state = Eigen::Matrix<double, 6, 1>::Zero() |
|
Eigen::Matrix< double, 6, 1 > | base_pose_commands = Eigen::Matrix<double, 6, 1>::Zero() |
|
double | lin_vel_x = 0.0 |
| The desired linear robot velocity in the body frame's x direction. More...
|
|
double | lin_vel_y = 0.0 |
| The desired linear robot velocity in the body frame's y direction. More...
|
|
double | ang_vel_z = 0.0 |
| The desired angular robot velocity around the robot's z axis. More...
|
|
double | _lin_vel_x_estimated = 0.0 |
|
double | _lin_vel_y_estimated = 0.0 |
|
double | _ang_vel_z_estimated = 0.0 |
|
double | _lin_vel_z_measured = 0.0 |
|
double | _ang_vel_x_measured = 0.0 |
|
double | _ang_vel_y_measured = 0.0 |
|
double | nominal_base_height = 0.35 |
|
Definition at line 5 of file gait_controller.h.