Class TFStatic

Inheritance Relationships

Derived Types

Class Documentation

class TFStatic

TFStatic object to publish static transforms in TF.

Subclassed by as2::sensors::Camera, as2::sensors::Gimbal, as2::sensors::Sensor< T >

Public Functions

explicit TFStatic(rclcpp::Node *node_ptr)

Construct a new TFStatic object.

virtual ~TFStatic()

Destroy the TFStatic object.

virtual void setStaticTransform(const geometry_msgs::msg::TransformStamped &transformStamped)

Set the Static Transform in TF.

Parameters:

transformStamped – TransformStamped message

virtual void setStaticTransform(const std::string &frame_id, const std::string &parent_frame_id, float x, float y, float z, float qx, float qy, float qz, float qw)

Set the Static Transform in TF.

Parameters:
  • frame_id – Frame ID

  • parent_frame_id – Parent Frame ID

  • x – X position (m)

  • y – Y position (m)

  • z – Z position (m)

  • qx – Quaternion X

  • qy – Quaternion Y

  • qz – Quaternion Z

  • qw – Quaternion W

virtual void setStaticTransform(const std::string &frame_id, const std::string &parent_frame_id, float x, float y, float z, float roll, float pitch, float yaw)

Set the Static Transform in TF.

Parameters:
  • frame_id – Frame ID

  • parent_frame_id – Parent Frame ID

  • x – X position (m)

  • y – Y position (m)

  • z – Z position (m)

  • roll – Roll (rad)

  • pitch – Pitch (rad)

  • yaw – Yaw (rad)

const rclcpp::Node *getNode() const

Get the Node Pointer object.

Returns:

rclcpp::Node* Node pointer