Class WalkVisualizer

Inheritance Relationships

Base Type

  • public bitbots_splines::AbstractVisualizer

Class Documentation

class bitbots_quintic_walk::WalkVisualizer : public bitbots_splines::AbstractVisualizer

Public Functions

explicit WalkVisualizer(rclcpp::Node::SharedPtr node, walking::Params::Node::Tf tf_config)
visualization_msgs::msg::Marker createArrowMarker(const std::string &name_space, const std::string &frame, const geometry_msgs::msg::Pose &pose, const std_msgs::msg::ColorRGBA &color)
std::pair<bitbots_quintic_walk::msg::WalkEngineDebug, visualization_msgs::msg::MarkerArray> buildEngineDebugMsgs(WalkResponse response)
std::pair<bitbots_quintic_walk::msg::WalkDebug, visualization_msgs::msg::MarkerArray> buildIKDebugMsgs(WalkResponse response, moveit::core::RobotStatePtr current_state, bitbots_splines::JointGoals joint_goals)
visualization_msgs::msg::MarkerArray buildWalkMarkers(WalkResponse response)
void init(moveit::core::RobotModelPtr kinematic_model)
void publishDebug(const WalkResponse &current_response, const moveit::core::RobotStatePtr &current_state, const bitbots_splines::JointGoals &motor_goals)
inline std_msgs::msg::ColorRGBA colorFactory(double r, double g, double b)

Public Members

const std_msgs::msg::ColorRGBA BLACK = colorFactory(0.0, 0.0, 0.0)
const std_msgs::msg::ColorRGBA BLUE = colorFactory(0.0, 0.0, 1.0)
const std_msgs::msg::ColorRGBA GREEN = colorFactory(0.0, 1.0, 0.0)
const std_msgs::msg::ColorRGBA ORANGE = colorFactory(1.0, 0.5, 0.0)
const std_msgs::msg::ColorRGBA RED = colorFactory(1.0, 0.0, 0.0)
const std_msgs::msg::ColorRGBA WHITE = colorFactory(1.0, 1.0, 1.0)
const std_msgs::msg::ColorRGBA YELLOW = colorFactory(1.0, 1.0, 0.0)

Private Members

rclcpp::Node::SharedPtr node_
walking::Params::Node::Tf tf_config_
rclcpp::Publisher<bitbots_quintic_walk::msg::WalkDebug>::SharedPtr pub_debug_
rclcpp::Publisher<bitbots_quintic_walk::msg::WalkEngineDebug>::SharedPtr pub_engine_debug_
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_debug_marker_
moveit::core::RobotModelPtr kinematic_model_