Class Gimbal

Inheritance Relationships

Base Types

Class Documentation

class Gimbal : public as2::sensors::TFStatic, protected as2::sensors::TFDynamic, protected as2::sensors::GenericSensor, protected as2::sensors::SensorData<geometry_msgs::msg::PoseStamped>

Class to handle the gimbal sensor.

Public Functions

explicit Gimbal(const std::string &gimbal_id, const std::string &gimbal_base_id, as2::Node *node_ptr, const float pub_freq = -1.0f, bool add_sensor_measurements_base = true)

Construct a new Gimbal object.

Parameters:
  • gimbal_id – Frame ID of the gimbal

  • gimbal_base_id – Frame ID of the gimbal base

  • node_ptr – Pointer to the node

  • pub_freq – Frequency to publish the data (-1 to publish every time updateData is called)

  • add_sensor_measurements_base – Add “sensor_measurements” to the topic name

virtual ~Gimbal()

Destroy the Gimbal object.

void setGimbalBaseTransform(const geometry_msgs::msg::Transform &gimbal_base_transform, const std::string &gimbal_parent_frame_id = "base_link")

Set the gimbal base transformation respect to the parent frame.

Parameters:
  • gimbal_base_transform – Transform message

  • gimbal_parent_frame_id – Parent frame ID (default is “base_link”)

void updateData(const geometry_msgs::msg::PoseStamped &pose_msg)

Update the gimbal transformation respect to the base.

Parameters:

pose_msg – Pose message

void updateData(const geometry_msgs::msg::QuaternionStamped &orientation_msg)

Update the gimbal transformation respect to the base.

Parameters:

pose_msg – Pose message

const std::string &getGimbalFrameId() const

Get the Gimbal Frame ID.

Returns:

const std::string& Frame ID of the gimbal

const std::string &getGimbalBaseFrameId() const

Get the Gimbal Base Frame ID.

Returns:

const std::string& Frame ID of the gimbal base

Protected Functions

virtual void publishData()

Publish the data in a topic and in TF.

Protected Attributes

std::string gimbal_frame_id_
std::string gimbal_base_frame_id_
geometry_msgs::msg::TransformStamped gimbal_transform_