Class WalkNode
Defined in File walk_node.hpp
Inheritance Relationships
Base Type
public rclcpp::Node
Class Documentation
-
class bitbots_quintic_walk::WalkNode : public rclcpp::Node
Public Functions
-
explicit WalkNode(std::string ns = "", std::vector<rclcpp::Parameter> parameters = {})
-
bitbots_msgs::msg::JointCommand step(double dt)
-
geometry_msgs::msg::Pose get_right_foot_pose()
Small helper method to get foot position via python wrapper
-
geometry_msgs::msg::Pose get_left_foot_pose()
-
void reset()
Reset everything to initial idle state.
Reset walk to any given state. Necessary for using this as reference in learning.
-
void run()
This is the main loop which takes care of stopping and starting of the walking. A small state machine is tracking in which state the walking is and builds the trajectories accordingly.
-
void initializeEngine()
Initialize internal WalkEngine to correctly zeroed, usable state
Sets the current state of the robot
- Parameters
msg – The current state
-
WalkEngine *getEngine()
-
moveit::core::RobotModelPtr *get_kinematic_model()
-
nav_msgs::msg::Odometry getOdometry()
-
rcl_interfaces::msg::SetParametersResult onSetParameters(const std::vector<rclcpp::Parameter> ¶meters)
-
void publish_debug()
-
rclcpp::TimerBase::SharedPtr startTimer()
-
double getTimerFreq()
Private Members
-
OnSetParametersCallbackHandle::SharedPtr callback_handle_
-
walking::ParamListener param_listener_
-
walking::Params config_
-
std::string odom_frame_
-
std::string base_link_frame_
-
std::string l_sole_frame_
-
std::string r_sole_frame_
-
WalkRequest current_request_
-
bool first_run_
-
double last_ros_update_time_
-
int robot_state_
-
int current_support_foot_
-
int odom_counter_
-
WalkRequest last_request_
-
WalkResponse current_response_
-
WalkResponse current_stabilized_response_
-
bitbots_splines::JointGoals motor_goals_
-
Eigen::Vector3d max_step_linear_
Saves max values we can move in a single step as [x-direction, y-direction, z-rotation]. Is used to limit _currentOrders to sane values
-
bitbots_quintic_walk::WalkEngine walk_engine_
-
nav_msgs::msg::Odometry odom_msg_
-
rclcpp::Publisher<bitbots_msgs::msg::JointCommand>::SharedPtr pub_controller_command_
-
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr pub_odometry_
-
rclcpp::Publisher<biped_interfaces::msg::Phase>::SharedPtr pub_support_
-
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr step_sub_
-
rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr cmd_vel_sub_
-
rclcpp::Subscription<bitbots_msgs::msg::RobotControlState>::SharedPtr robot_state_sub_
-
rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_
-
rclcpp::Subscription<std_msgs::msg::Bool>::SharedPtr kick_sub_
-
rclcpp::Subscription<sensor_msgs::msg::Imu>::SharedPtr imu_sub_
-
rclcpp::Subscription<bitbots_msgs::msg::FootPressure>::SharedPtr pressure_sub_left_
-
rclcpp::Subscription<bitbots_msgs::msg::FootPressure>::SharedPtr pressure_sub_right_
-
std::shared_ptr<robot_model_loader::RobotModelLoader> robot_model_loader_
-
moveit::core::RobotModelPtr kinematic_model_
-
moveit::core::RobotStatePtr current_state_
-
WalkStabilizer stabilizer_
-
WalkVisualizer visualizer_
-
double current_trunk_fused_pitch_
-
double current_trunk_fused_roll_
-
double current_fly_pressure_
-
double current_fly_effort_
-
double roll_vel_
-
double pitch_vel_
-
bool got_new_goals_
-
explicit WalkNode(std::string ns = "", std::vector<rclcpp::Parameter> parameters = {})