Class DynupEngine
Defined in File dynup_engine.hpp
Inheritance Relationships
Base Type
public bitbots_splines::AbstractEngine< DynupRequest, DynupResponse >
Class Documentation
-
class bitbots_dynup::DynupEngine : public bitbots_splines::AbstractEngine<DynupRequest, DynupResponse>
Public Functions
-
void init(double arm_offset_y, double arm_offset_z)
-
DynupResponse update(double dt) override
-
void setGoals(const DynupRequest &goals) override
-
void publishDebug()
-
int getPercentDone() const override
-
double getDuration() const
-
DynupDirection getDirection()
-
bool isStabilizingNeeded()
-
bool isHeadZero()
-
bitbots_splines::PoseSpline getRFootSplines() const
-
bitbots_splines::PoseSpline getLHandSplines() const
-
bitbots_splines::PoseSpline getRHandSplines() const
-
bitbots_splines::PoseSpline getLFootSplines() const
-
void setParams(bitbots_dynup::Params::Engine params)
-
void reset() override
-
void reset(double time)
-
void publishArrowMarker(std::string name_space, std::string frame, geometry_msgs::msg::Pose pose, float r, float g, float b, float a)
Private Functions
-
geometry_msgs::msg::PoseStamped getCurrentPose(bitbots_splines::PoseSpline spline, std::string frame_id)
-
bitbots_splines::PoseSpline initializeSpline(geometry_msgs::msg::Pose pose, bitbots_splines::PoseSpline spline)
-
double calcFrontSplines()
-
double calcBackSplines()
-
double calcWalkreadySplines(double time = 0, double travel_time = 0)
-
double calcDescendSplines(double time = 0)
Private Members
-
rclcpp::Node::SharedPtr node_
-
bitbots_dynup::Params::Engine params_
-
int marker_id_ = 1
-
double time_ = 0
-
double duration_ = 0
-
double arm_offset_y_ = 0
-
double arm_offset_z_ = 0
-
tf2::Transform offset_left_
-
tf2::Transform offset_right_
-
DynupDirection direction_ = DynupDirection::WALKREADY
-
bitbots_splines::PoseSpline l_foot_spline_
-
bitbots_splines::PoseSpline l_hand_spline_
-
bitbots_splines::PoseSpline r_foot_spline_
-
bitbots_splines::PoseSpline r_hand_spline_
-
DynupResponse goals_
-
std::shared_ptr<rclcpp::Node> walking_param_node_
-
std::shared_ptr<rclcpp::SyncParametersClient> walking_param_client_
-
rclcpp::Publisher<bitbots_dynup::msg::DynupEngineDebug>::SharedPtr pub_engine_debug_
-
rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr pub_debug_marker_
-
void init(double arm_offset_y, double arm_offset_z)