Class GroundTruth

Inheritance Relationships

Base Type

Class Documentation

class GroundTruth : protected as2::sensors::GenericSensor

Class to handle the ground truth of the platform.

Public Functions

explicit GroundTruth(as2::Node *node_ptr, const float pub_freq = -1, const std::string &topic_name_base = "")

Construct a new GroundTruth object.

Parameters:
  • node_ptr – Pointer to the node

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

  • topic_name_base – Base name of the topics. Default is “”

virtual ~GroundTruth()

Destroy the GroundTruth object.

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

Update the data of the ground truth.

Parameters:

pose_msg – Pose message

void updateData(const geometry_msgs::msg::TwistStamped &twist_msg)

Update the data of the ground truth.

Parameters:

twist_msg – Twist message

void updateData(const geometry_msgs::msg::PoseStamped &pose_msg, const geometry_msgs::msg::TwistStamped &twist_msg)

Update the data of the ground truth.

Parameters:
  • pose_msg – Pose message

  • twist_msg – Twist message

Protected Functions

virtual void publishData() override

User must implement the data publishing in this function.

Protected Attributes

std::shared_ptr<SensorData<geometry_msgs::msg::PoseStamped>> pose_sensor_
std::shared_ptr<SensorData<geometry_msgs::msg::TwistStamped>> twist_sensor_