Ignition Gazebo

API Reference

5.0.0
Visualization.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 
18 #ifndef IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_
19 #define IGNITION_GAZEBO_SYSTEMS_OPTICAL_TACTILE_PLUGIN_VISUALIZATION_HH_
20 
21 #include <memory>
22 #include <string>
23 
24 #include <ignition/gazebo/config.hh>
27 
29 
30 namespace ignition
31 {
32 namespace gazebo
33 {
34 // Inline bracket to help doxygen filtering.
35 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE
36 {
37 namespace systems
38 {
39 namespace optical_tactile_sensor
40 {
41  // This class handles the configuration and process of visualizing the
42  // different elements needed for the Optical Tactile Sensor plugin.
43  // Terminology:
44  // "Contacts" refers to data from the contact sensor based on physics.
45  // "Normal forces" refers to post-processed data from the depth camera based
46  // purely on imagery.
47  // These two sets of data are currently disjoint and visualized separately.
49  {
59  std::string &_modelName,
60  ignition::math::Vector3d &_sensorSize,
61  double &_forceLength,
62  float &_cameraUpdateRate,
63  ignition::math::Pose3f &_depthCameraOffset,
64  int &_visualizationResolution);
65 
69  private: void InitializeSensorMarkerMsg(
70  ignition::msgs::Marker &_sensorMarkerMsg);
71 
76  public: void RequestSensorMarkerMsg(
77  ignition::math::Pose3f const &_sensorPose);
78 
82  private: void InitializeContactsMarkerMsg(
83  ignition::msgs::Marker &_contactsMarkerMsg);
84 
89  public: void AddContactToMarkerMsg(
90  ignition::msgs::Contact const &_contact,
91  ignition::msgs::Marker &_contactsMarkerMsg);
92 
95  public: void RequestContactsMarkerMsg(
96  components::ContactSensorData const *_contacts);
97 
103  private: void InitializeNormalForcesMarkerMsgs(
104  ignition::msgs::Marker &_positionMarkerMsg,
105  ignition::msgs::Marker &_forceMarkerMsg);
106 
119  public: void AddNormalForceToMarkerMsgs(
120  ignition::msgs::Marker &_positionMarkerMsg,
121  ignition::msgs::Marker &_forceMarkerMsg,
122  ignition::math::Vector3f &_position,
123  ignition::math::Vector3f &_normalForce,
124  ignition::math::Pose3f &_sensorWorldPose);
125 
132  public: void RequestNormalForcesMarkerMsgs(
133  ignition::msgs::Marker &_positionMarkerMsg,
134  ignition::msgs::Marker &_forceMarkerMsg);
135 
138 
140  private: ignition::transport::Node node;
141 
143  private: std::string modelName;
144 
146  private: ignition::math::Vector3d sensorSize;
147 
149  private: double forceLength;
150 
152  private: float cameraUpdateRate;
153 
155  private: ignition::math::Pose3f depthCameraOffset;
156 
158  private: int visualizationResolution;
159 
161  private: bool normalForcesMsgsAreInitialized{false};
162  };
163 } // namespace optical_tactile_sensor
164 } // namespace systems
165 } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE
166 } // namespace gazebo
167 } // namespace ignition
168 
169 #endif
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 RequestNormalForcesMarkerMsgs(ignition::msgs::Marker &_positionMarkerMsg, ignition::msgs::Marker &_forceMarkerMsg)
Request the "/marker" service for the marker messages representing the normal forces.
void RequestContactsMarkerMsg(components::ContactSensorData const *_contacts)
Request the "/marker" service for the contacts marker.
STL class.
OpticalTactilePluginVisualization(std::string &_modelName, ignition::math::Vector3d &_sensorSize, double &_forceLength, float &_cameraUpdateRate, ignition::math::Pose3f &_depthCameraOffset, int &_visualizationResolution)
Constructor.
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.
void RequestSensorMarkerMsg(ignition::math::Pose3f const &_sensorPose)
Request the "/marker" service for the sensor marker. This can be helpful when debbuging, given that there shouldn&#39;t be a visual tag in the plugin&#39;s model.
A component type that wraps any data type. The intention is for this class to be used to create simpl...
Definition: Component.hh:316
This library is part of the Ignition Robotics project.