Main Page
Related Pages
Namespaces
Classes
Files
File List
File Members
include
jsk_pcl_ros
octomap_server_contact.h
Go to the documentation of this file.
1
// -*- mode: c++ -*-
2
/*********************************************************************
3
* Software License Agreement (BSD License)
4
*
5
* Copyright (c) 2015, JSK Lab
6
* All rights reserved.
7
*
8
* Redistribution and use in source and binary forms, with or without
9
* modification, are permitted provided that the following conditions
10
* are met:
11
*
12
* * Redistributions of source code must retain the above copyright
13
* notice, this list of conditions and the following disclaimer.
14
* * Redistributions in binary form must reproduce the above
15
* copyright notice, this list of conditions and the following
16
* disclaimer in the documentation and/o2r other materials provided
17
* with the distribution.
18
* * Neither the name of the JSK Lab nor the names of its
19
* contributors may be used to endorse or promote products derived
20
* from this software without specific prior written permission.
21
*
22
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33
* POSSIBILITY OF SUCH DAMAGE.
34
*********************************************************************/
35
36
#ifndef OCTOMAP_SERVER_OCTOMAPSERVER_CONTACT_H_
37
#define OCTOMAP_SERVER_OCTOMAPSERVER_CONTACT_H_
38
39
#include <
ros/ros.h
>
40
#include <
jsk_topic_tools/diagnostic_nodelet.h
>
41
42
#define NDEBUG
43
#include <
octomap_server/OctomapServer.h
>
44
#include <
jsk_pcl_ros/OcTreeContact.h
>
45
#include <jsk_recognition_msgs/ContactSensorArray.h>
46
#include <
jsk_pcl_ros/self_mask_named_link.h
>
47
48
using
octomap_server::OctomapServer
;
49
50
namespace
jsk_pcl_ros
51
{
52
class
OctomapServerContact
:
public
OctomapServer
,
53
public
jsk_topic_tools::DiagnosticNodelet
54
{
55
public
:
56
OctomapServerContact
(
const
ros::NodeHandle
& privateNh =
ros::NodeHandle
(
"~"
));
57
virtual
~OctomapServerContact
();
58
59
virtual
void
insertProximityCallback
(
const
sensor_msgs::PointCloud2::ConstPtr&
cloud
);
60
virtual
void
insertScanProximity
(
const
tf::Point
& sensorOriginTf,
const
PCLPointCloud
& pc);
61
virtual
void
initContactSensor
(
const
ros::NodeHandle
& privateNh);
62
virtual
void
insertContactSensor
(
const
jsk_recognition_msgs::ContactSensorArray::ConstPtr&
msg
);
63
virtual
void
insertContactSensorCallback
(
const
jsk_recognition_msgs::ContactSensorArray::ConstPtr& msg);
64
65
virtual
void
publishAll
(
const
ros::Time
& rostime);
66
virtual
void
subscribe
() {};
67
virtual
void
unsubscribe
() {};
68
69
protected
:
70
virtual
void
onInit
();
71
ros::Publisher
m_unknownPointCloudPub
,
m_umarkerPub
;
72
message_filters::Subscriber<sensor_msgs::PointCloud2>
*
m_pointProximitySub
;
73
tf::MessageFilter<sensor_msgs::PointCloud2>
*
m_tfPointProximitySub
;
74
ros::Publisher
m_frontierPointCloudPub
,
m_fromarkerPub
;
75
message_filters::Subscriber<jsk_recognition_msgs::ContactSensorArray>
m_contactSensorSub
;
76
boost::shared_ptr<tf::MessageFilter<jsk_recognition_msgs::ContactSensorArray>
>
m_tfContactSensorSub
;
77
ros::ServiceServer
m_octomapBinaryService
,
m_octomapFullService
,
m_clearBBXService
,
m_resetService
;
78
79
std_msgs::ColorRGBA
m_colorUnknown
;
80
std_msgs::ColorRGBA
m_colorFrontier
;
81
82
bool
m_publishUnknownSpace
;
83
double
m_offsetVisualizeUnknown
;
84
85
bool
m_publishFrontierSpace
;
86
87
double
m_maxRangeProximity
;
88
89
double
m_occupancyMinX
;
90
double
m_occupancyMaxX
;
91
double
m_occupancyMinY
;
92
double
m_occupancyMaxY
;
93
94
bool
m_useContactSurface
;
95
96
boost::shared_ptr<robot_self_filter::SelfMaskNamedLink>
m_selfMask
;
97
98
octomap::OcTreeContact
*
m_octreeContact
;
99
};
100
}
101
102
#endif
jsk_pcl_ros::OctomapServerContact::m_pointProximitySub
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointProximitySub
Definition:
octomap_server_contact.h:72
jsk_pcl_ros::OctomapServerContact::~OctomapServerContact
virtual ~OctomapServerContact()
Definition:
octomap_server_contact_nodelet.cpp:118
tf::MessageFilter< sensor_msgs::PointCloud2 >
jsk_pcl_ros::OctomapServerContact::m_tfPointProximitySub
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointProximitySub
Definition:
octomap_server_contact.h:73
ros::NodeHandle
jsk_pcl_ros::OctomapServerContact::m_occupancyMinY
double m_occupancyMinY
Definition:
octomap_server_contact.h:91
jsk_pcl_ros::OctomapServerContact::insertContactSensor
virtual void insertContactSensor(const jsk_recognition_msgs::ContactSensorArray::ConstPtr &msg)
Definition:
octomap_server_contact_nodelet.cpp:307
jsk_pcl_ros::OctomapServerContact::m_octomapFullService
ros::ServiceServer m_octomapFullService
Definition:
octomap_server_contact.h:77
jsk_pcl_ros::OctomapServerContact::insertScanProximity
virtual void insertScanProximity(const tf::Point &sensorOriginTf, const PCLPointCloud &pc)
Definition:
octomap_server_contact_nodelet.cpp:209
ros::Time
jsk_pcl_ros::OctomapServerContact::m_selfMask
boost::shared_ptr< robot_self_filter::SelfMaskNamedLink > m_selfMask
Definition:
octomap_server_contact.h:96
jsk_pcl_ros::OctomapServerContact::m_frontierPointCloudPub
ros::Publisher m_frontierPointCloudPub
Definition:
octomap_server_contact.h:74
jsk_pcl_ros::OctomapServerContact::m_clearBBXService
ros::ServiceServer m_clearBBXService
Definition:
octomap_server_contact.h:77
jsk_pcl_ros::OctomapServerContact::m_publishUnknownSpace
bool m_publishUnknownSpace
Definition:
octomap_server_contact.h:82
jsk_pcl_ros::OctomapServerContact::m_umarkerPub
ros::Publisher m_umarkerPub
Definition:
octomap_server_contact.h:71
jsk_pcl_ros::OctomapServerContact::m_maxRangeProximity
double m_maxRangeProximity
Definition:
octomap_server_contact.h:87
jsk_pcl_ros::OctomapServerContact::m_publishFrontierSpace
bool m_publishFrontierSpace
Definition:
octomap_server_contact.h:85
diagnostic_nodelet.h
jsk_pcl_ros::OctomapServerContact::initContactSensor
virtual void initContactSensor(const ros::NodeHandle &privateNh)
Definition:
octomap_server_contact_nodelet.cpp:121
boost::shared_ptr
jsk_pcl_ros::OctomapServerContact::m_offsetVisualizeUnknown
double m_offsetVisualizeUnknown
Definition:
octomap_server_contact.h:83
jsk_pcl_ros::OctomapServerContact::publishAll
virtual void publishAll(const ros::Time &rostime)
Definition:
octomap_server_contact_nodelet.cpp:458
jsk_pcl_ros::OctomapServerContact
Definition:
octomap_server_contact.h:52
octomap_server::OctomapServer
jsk_pcl_ros::OctomapServerContact::m_resetService
ros::ServiceServer m_resetService
Definition:
octomap_server_contact.h:77
jsk_pcl_ros::OctomapServerContact::m_tfContactSensorSub
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::ContactSensorArray > > m_tfContactSensorSub
Definition:
octomap_server_contact.h:76
ros::ServiceServer
jsk_pcl_ros::OctomapServerContact::insertContactSensorCallback
virtual void insertContactSensorCallback(const jsk_recognition_msgs::ContactSensorArray::ConstPtr &msg)
Definition:
octomap_server_contact_nodelet.cpp:451
jsk_pcl_ros::OctomapServerContact::m_occupancyMaxY
double m_occupancyMaxY
Definition:
octomap_server_contact.h:92
pose_with_covariance_sample.msg
msg
Definition:
pose_with_covariance_sample.py:22
OctomapServer.h
OcTreeContact.h
jsk_pcl_ros::OctomapServerContact::m_octreeContact
octomap::OcTreeContact * m_octreeContact
Definition:
octomap_server_contact.h:98
jsk_pcl_ros::OctomapServerContact::m_occupancyMaxX
double m_occupancyMaxX
Definition:
octomap_server_contact.h:90
jsk_pcl_ros::OctomapServerContact::m_colorFrontier
std_msgs::ColorRGBA m_colorFrontier
Definition:
octomap_server_contact.h:80
ros.h
jsk_pcl_ros::OctomapServerContact::subscribe
virtual void subscribe()
Definition:
octomap_server_contact.h:66
jsk_pcl_ros::OctomapServerContact::m_fromarkerPub
ros::Publisher m_fromarkerPub
Definition:
octomap_server_contact.h:74
jsk_pcl_ros::OctomapServerContact::m_colorUnknown
std_msgs::ColorRGBA m_colorUnknown
Definition:
octomap_server_contact.h:79
jsk_pcl_ros::OctomapServerContact::m_octomapBinaryService
ros::ServiceServer m_octomapBinaryService
Definition:
octomap_server_contact.h:77
jsk_pcl_ros::OctomapServerContact::insertProximityCallback
virtual void insertProximityCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
Definition:
octomap_server_contact_nodelet.cpp:174
jsk_pcl_ros::OctomapServerContact::m_contactSensorSub
message_filters::Subscriber< jsk_recognition_msgs::ContactSensorArray > m_contactSensorSub
Definition:
octomap_server_contact.h:75
self_mask_named_link.h
jsk_pcl_ros::OctomapServerContact::m_useContactSurface
bool m_useContactSurface
Definition:
octomap_server_contact.h:94
jsk_pcl_ros::OctomapServerContact::OctomapServerContact
OctomapServerContact(const ros::NodeHandle &privateNh=ros::NodeHandle("~"))
Definition:
octomap_server_contact_nodelet.cpp:45
message_filters::Subscriber< sensor_msgs::PointCloud2 >
ros::Publisher
cloud
cloud
octomap::OcTreeContact
This is a inherited class of OcTree. The probability of contact sensor model is defined.
Definition:
OcTreeContact.h:48
octomap_server::OctomapServer::PCLPointCloud
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
jsk_pcl_ros::OctomapServerContact::m_occupancyMinX
double m_occupancyMinX
Definition:
octomap_server_contact.h:89
jsk_pcl_ros::OctomapServerContact::unsubscribe
virtual void unsubscribe()
Definition:
octomap_server_contact.h:67
jsk_pcl_ros::OctomapServerContact::onInit
virtual void onInit()
Definition:
octomap_server_contact_nodelet.cpp:844
jsk_pcl_ros::OctomapServerContact::m_unknownPointCloudPub
ros::Publisher m_unknownPointCloudPub
Definition:
octomap_server_contact.h:71
tf::Vector3
jsk_pcl_ros
Definition:
add_color_from_image.h:51
jsk_topic_tools::DiagnosticNodelet
jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47