Quad-SDK
Loading...
Searching...
No Matches
contact_plugin.h
1/*
2MIT License (modified)
3
4Copyright (c) 2018 The Trustees of the University of Pennsylvania
5Authors:
6Vasileios Vasilopoulos <vvasilo@seas.upenn.edu>
7
8Permission is hereby granted, free of charge, to any person obtaining a copy
9of this **file** (the "Software"), to deal
10in the Software without restriction, including without limitation the rights
11to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12copies of the Software, and to permit persons to whom the Software is
13furnished to do so, subject to the following conditions:
14
15The above copyright notice and this permission notice shall be included in all
16copies or substantial portions of the Software.
17
18THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
23OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
24SOFTWARE.
25*/
26
27#ifndef _GAZEBO_CONTACT_PLUGIN_HH_
28#define _GAZEBO_CONTACT_PLUGIN_HH_
29
30#include <geometry_msgs/Vector3.h>
31#include <quad_msgs/ContactMode.h>
32#include <ros/ros.h>
33
34#include <gazebo/gazebo.hh>
35#include <gazebo/sensors/sensors.hh>
36#include <string>
37
38namespace gazebo {
40class ContactPlugin : public SensorPlugin {
42 public:
44
45 // \brief ROS related members
46 private:
47 std::unique_ptr<ros::NodeHandle> rosNode;
48
49 private:
50 ros::Publisher contact_publisher;
51
53 public:
54 virtual ~ContactPlugin();
55
59 public:
60 virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf);
61
63 private:
64 virtual void OnUpdate();
65
67 private:
68 sensors::ContactSensorPtr parentSensor;
69
72 private:
73 event::ConnectionPtr updateConnection;
74};
75} // namespace gazebo
76#endif
An example plugin for a contact sensor.
Definition contact_plugin.h:40
sensors::ContactSensorPtr parentSensor
Pointer to the contact sensor.
Definition contact_plugin.h:68
event::ConnectionPtr updateConnection
Connection that maintains a link between the contact sensor's updated signal and the OnUpdate callbac...
Definition contact_plugin.h:73
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
Load the sensor plugin.
Definition contact_plugin.cpp:39
ContactPlugin()
Constructor.
Definition contact_plugin.cpp:33
virtual void OnUpdate()
Callback that receives the contact sensor's update signal.
Definition contact_plugin.cpp:74
virtual ~ContactPlugin()
Destructor.
Definition contact_plugin.cpp:36