Class WalkEngine
Defined in File walk_engine.hpp
Inheritance Relationships
Base Type
public bitbots_splines::AbstractEngine< WalkRequest, WalkResponse >
Class Documentation
-
class bitbots_quintic_walk::WalkEngine : public bitbots_splines::AbstractEngine<WalkRequest, WalkResponse>
QuinticWalk
Holonomic and open loop walk generator based on footstep control and quintic splines in cartesian space. Expressed all target state in cartesian space with respect to current support foot.
Public Functions
-
WalkResponse update(double dt) override
-
void setGoals(const WalkRequest &goals) override
-
void reset() override
-
int getPercentDone() const override
-
void setConfig(walking::Params::Engine config)
Updates the engine configuration.
-
void reset(WalkState state, double phase, std::array<double, 4> step, bool stop_walk, bool walkable_state, bool reset_odometry)
Resets the engine to any given state. Necessary for using it as reference in learning.
-
double getPhase() const
Return current walk phase between 0 and 1
-
double getTrajsTime() const
Return current time between 0 and half period for trajectories evaluation
-
bool isLeftSupport() const
Return if true if left is current support foot
-
bool isDoubleSupport()
Return true if both feet are currently on the ground
-
void requestKick(bool left)
-
void requestPause()
-
void endStep()
Ends the current step earlier. Useful if foot hits ground to early.
-
void setPhaseRest(bool active)
-
double getFreq() const
-
double getWantedTrunkPitch()
-
void setPauseDuration(double duration)
-
void setForceSmoothStepTransition(bool force)
-
tf2::Transform getLeft()
-
tf2::Transform getRight()
Public Members
-
walking::Params::Engine config_
Private Types
Private Functions
-
void updatePhase(double dt)
-
void buildTrajectories(TrajectoryType type)
-
void buildWalkDisableTrajectories(bool foot_in_idle_position)
-
void saveCurrentRobotState()
-
WalkResponse createResponse()
Compute current cartesian target from trajectories and assign it to given model through inverse kinematics. Return false is the target is unreachable.
-
void stepFromSupport(const tf2::Transform &diff)
Set the target pose of current support foot during next support phase and update support foot. The target foot pose diff is given with respect to next support foot pose (current flying foot target).
-
void stepFromOrders(const std::vector<double> &linear_orders, double angular_z)
Set target pose of current support foot using diff orders. Zero vector means in place walking. Special handle of lateral and turn step to avoid foot collision.
-
tf2::Vector3 getLastEuler()
Small helper method to get euler angle instead of quaternion.
-
tf2::Vector3 getNextEuler()
Private Members
-
rclcpp::Node::SharedPtr node_
-
WalkRequest request_
-
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr callback_handle_
-
bitbots_splines::SmoothSpline is_double_support_spline_
-
bitbots_splines::SmoothSpline is_left_support_foot_spline_
-
bitbots_splines::PoseSpline trunk_spline_
-
bitbots_splines::PoseSpline foot_spline_
-
double phase_ = 0.0
-
double last_phase_ = 0.0
-
double time_paused_ = 0.0
-
double pause_duration_ = 0.0
-
bool pause_requested_ = false
-
bool phase_rest_active_ = false
-
bool left_kick_requested_ = false
-
bool right_kick_requested_ = false
-
bool is_left_support_foot_ = false
-
bool force_smooth_step_transition_ = false
-
tf2::Transform support_to_last_
-
tf2::Transform support_to_next_
-
tf2::Transform left_in_world_
-
tf2::Transform right_in_world_
-
tf2::Vector3 trunk_pos_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 trunk_pos_vel_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 trunk_pos_acc_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 trunk_orientation_pos_at_last_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 trunk_orientation_vel_at_last_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 trunk_orientation_acc_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 foot_pos_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 foot_pos_vel_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 foot_pos_acc_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 foot_orientation_pos_at_last_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 foot_orientation_vel_at_last_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
tf2::Vector3 foot_orientation_acc_at_foot_change_ = tf2::Vector3(0.0, 0.0, 0.0)
-
WalkResponse update(double dt) override