roch_sensorpc.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Yujin Robot.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Yujin Robot nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
44 #ifndef _ROCH_SENSORPC_HPP_
45 #define _ROCH_SENSORPC_HPP_
46 
47 /*****************************************************************************
48  ** Includes
49  *****************************************************************************/
50 
51 #include <ros/ros.h>
52 
53 #include <sensor_msgs/PointCloud2.h>
54 
55 #include <roch_msgs/SensorState.h>
56 
57 /*****************************************************************************
58  ** Namespace
59  *****************************************************************************/
60 
61 namespace roch_sensorpc
62 {
63 
68 {
69 public:
71  : P_INF_X(+100*sin(0.34906585)),
72  P_INF_Y(+100*cos(0.34906585)),
73  N_INF_Y(-100*cos(0.34906585)),
75  ult_enable_(true),psd_enable_(true),cliff_enable_(true),
76  nh(nh_),private_nh_(private_nh){ onInit(); }
78 
79  void onInit();
80 
81 private:
82  const float P_INF_X; // somewhere out of reach from the robot (positive x)
83  const float P_INF_Y; // somewhere out of reach from the robot (positive y)
84  const float N_INF_Y; // somewhere out of reach from the robot (negative y)
85  const float ZERO;
86 
87  uint8_t prev_leftcliff;
88  uint8_t prev_rightcliff;
89  uint8_t prev_leftult;
90  uint8_t prev_centerult;
91  uint8_t prev_rightult;
92  uint8_t prev_leftpsd;
93  uint8_t prev_centerpsd;
94  uint8_t prev_rightpsd;
95 
96  float pc_radius_;
97  float pc_height_;
98  float p_side_x_;
99  float p_side_y_;
100  float n_side_y_;
101 
105 
108 
111  sensor_msgs::PointCloud2 pointcloud_;
112 
117  void coreSensorCB(const roch_msgs::SensorState::ConstPtr& msg);
118 };
119 
120 } // namespace roch_bumper2pc
121 
122 #endif // _ROCH_SENSORPC_HPP_
sensor_msgs::PointCloud2 pointcloud_
void coreSensorCB(const roch_msgs::SensorState::ConstPtr &msg)
Core sensors state structure callback.
SensorPcNodelet(ros::NodeHandle nh_, ros::NodeHandle private_nh)
SensorPcNodelet class declaration.


roch_sensorpc
Author(s): Chen , Jorge Santos Simon
autogenerated on Mon Jun 10 2019 14:41:26