Class RobotInformation

Class Documentation

class RobotInformation

Public Types

typedef std::shared_ptr<RobotInformation> Ptr
typedef std::shared_ptr<const RobotInformation> ConstPtr

Public Functions

RobotInformation(const rclcpp::Node::SharedPtr &node, const TFPtr &tf_buffer, const std::string &global_frame, const std::string &robot_frame, const rclcpp::Duration &tf_timeout, const std::string &odom_topic = "odom")
bool getRobotPose(geometry_msgs::msg::PoseStamped &robot_pose) const

Computes the current robot pose (robot_frame_) in the global frame (global_frame_).

Parameters:

robot_pose – Reference to the robot_pose message object to be filled.

Returns:

true, if the current robot pose could be computed, false otherwise.

bool getRobotVelocity(geometry_msgs::msg::TwistStamped &robot_velocity) const

Returns the current robot velocity, as provided by the odometry helper.

Parameters:

robot_velocity – Reference to the robot_velocity message object to be filled.

Returns:

true, if the current robot velocity could be obtained, false otherwise.

bool isRobotStopped(double rot_stopped_velocity, double trans_stopped_velocity) const

Check whether the robot is stopped or not.

Parameters:
  • rot_stopped_velocity – The rotational velocity below which the robot is considered stopped

  • trans_stopped_velocity – The translational velocity below which the robot is considered stopped

Returns:

true if the robot is stopped, false otherwise

const std::string &getGlobalFrame() const
const std::string &getRobotFrame() const
const TF &getTransformListener() const
const rclcpp::Duration &getTfTimeout() const