Go to the documentation of this file.
18 #ifndef IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_
19 #define IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_
24 #include <gz/sim/config.hh>
26 #include <gz/msgs/marker.pb.h>
35 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
38 namespace optical_tactile_sensor
57 ignition::math::Vector3d &_sensorSize,
59 float &_cameraUpdateRate,
60 ignition::math::Pose3f &_depthCameraOffset);
65 private:
void InitializeSensorMarkerMsg(
66 ignition::msgs::Marker &_sensorMarkerMsg);
72 public:
void RequestSensorMarkerMsg(
73 ignition::math::Pose3f
const &_sensorPose);
78 private:
void InitializeContactsMarkerMsg(
79 ignition::msgs::Marker &_contactsMarkerMsg);
85 public:
void AddContactToMarkerMsg(
86 ignition::msgs::Contact
const &_contact,
87 ignition::msgs::Marker &_contactsMarkerMsg);
91 public:
void RequestContactsMarkerMsg(
99 private:
void InitializeNormalForcesMarkerMsgs(
100 ignition::msgs::Marker &_positionMarkerMsg,
101 ignition::msgs::Marker &_forceMarkerMsg);
115 public:
void AddNormalForceToMarkerMsgs(
116 ignition::msgs::Marker &_positionMarkerMsg,
117 ignition::msgs::Marker &_forceMarkerMsg,
118 ignition::math::Vector3f &_position,
119 ignition::math::Vector3f &_normalForce,
120 ignition::math::Pose3f &_sensorWorldPose);
128 public:
void RequestNormalForcesMarkerMsgs(
129 ignition::msgs::Marker &_positionMarkerMsg,
130 ignition::msgs::Marker &_forceMarkerMsg);
133 public:
void RemoveNormalForcesAndContactsMarkers();
136 private: ignition::transport::Node node;
142 private: ignition::math::Vector3d sensorSize;
145 private:
double forceLength;
148 private:
float cameraUpdateRate;
151 private: ignition::math::Pose3f depthCameraOffset;
154 private:
bool normalForcesMsgsAreInitialized{
false};
Definition: Visualization.hh:47
This library is part of the Gazebo project.
Definition: gz/sim/Actor.hh:33
void AddNormalForceToMarkerMsgs(ignition::msgs::Marker &_positionMarkerMsg, ignition::msgs::Marker &_forceMarkerMsg, ignition::math::Vector3f &_position, ignition::math::Vector3f &_normalForce, ignition::math::Pose3f &_sensorWorldPose)
Create a marker messages representing the normal force computed from depth camera.
OpticalTactilePluginVisualization(std::string &_modelName, ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, ignition::math::Pose3f &_depthCameraOffset)
Constructor.
A component type that wraps any data type. The intention is for this class to be used to create simpl...
Definition: gz/sim/components/Component.hh:324
void RequestSensorMarkerMsg(ignition::math::Pose3f const &_sensorPose)
Request the "/marker" service for the sensor marker. This can be helpful when debbuging,...
void RequestContactsMarkerMsg(components::ContactSensorData const *_contacts)
Request the "/marker" service for the contacts marker.
void AddContactToMarkerMsg(ignition::msgs::Contact const &_contact, ignition::msgs::Marker &_contactsMarkerMsg)
Add a contact to the marker message representing the contacts from the contact sensor based on physic...
void RemoveNormalForcesAndContactsMarkers()
Remove all normal forces and contact markers.
void RequestNormalForcesMarkerMsgs(ignition::msgs::Marker &_positionMarkerMsg, ignition::msgs::Marker &_forceMarkerMsg)
Request the "/marker" service for the marker messages representing the normal forces.