semio_ros  0.10.6
humanoid_sink_adapter.h
Go to the documentation of this file.
1 #ifndef _SEMIO_ROS_HUMANOIDSINKADAPTER_H_
2 #define _SEMIO_ROS_HUMANOIDSINKADAPTER_H_
3 
5 #include <ros/node_handle.h>
6 #include <string>
7 
8 namespace semio
9 {
10 
11 namespace ros
12 {
13 
14 //! Utility class to simplify the creation of semio::HumanoidSink instances
16 {
17 protected:
18  //! NodeHandle copy for interfacing with ROS
19  ::ros::NodeHandle _nh_rel;
20  //! The type of sink to use by default if param mode is selected and the ROS param @b `_humanoid_sink/type` is not defined @sa getHumanoidSink()
21  std::string _default_sink;
22 
23 public:
24  /**
25  @param nh_rel @copybrief _nh_rel
26  @param default_sink @copybrief _default_sink
27  */
28  HumanoidSinkAdapter( ::ros::NodeHandle const & nh_rel, std::string const & default_sink = "ros" );
29 
30  //! Create a semio::HumanoidSink
31  /**
32  If the ROS param @b `_humanoid_sink/filter/smoothing` is defined, then a semio::HumanoidSmoothingFilter will be added to the sink's filter list. See @ref getHumanoidSink-ros-params "ROS Params" for more info.
33 
34  @param sink The type of sink to create
35  <table>
36  <tr><th>Value</th><th>Resulting pointer type</th><th>Notes</th></tr>
37  <tr><td>`"param"`</td><td>variable based on ROS param</td><td>Uses the value of the ROS param @b `_humanoid_sink/type` to set @p sink; defaults to #_default_sink defined during construction</td></tr>
38  <tr><td>`"ros"`</td><td>semio::ros::HumanoidSinkROS</td><td>Use ROS to sink humanoids; if the smoothing filter is enabled, creates the sink on topic @b `~humanoids/smoothed`</td></tr>
39  <tr><td>`"none"`</td><td>semio::ros::HumanoidSinkROS</td><td>Specialization of semio::ros::HumanoidSinkROS, connects to topic @b `/null`</td></tr>
40  </table>
41  @note `"none"` will be used if the value of @p sink is not recognized
42 
43  @anchor getHumanoidSink-ros-params
44  @par ROS Params
45  <table>
46  <tr><th>Name</th><th>Type</th><th>Default</th><th>Description</th></tr>
47  <tr><td>@b `_humanoid_sink/type`</td><td>string</td><td>#_default_sink</td><td>Type of sink to create when @p sink is `"param"`</td></tr>
48  <tr><td>@b `_humanoid_sink/filter/smoothing/add`</td><td>any</td><td>undefined</td><td>Define this parameter to add a default smoothing filter to outgoing humanoids (when no other smoothing params are defined)</td></tr>
49  <tr><td>@b `_humanoid_sink/filter/smoothing/position`</td><td>float64</td><td>undefined</td><td>The strength of the position component of the smoothing filter</td></tr>
50  <tr><td>@b `_humanoid_sink/filter/smoothing/orientation`</td><td>float64</td><td>undefined</td><td>The strength of the orientation component of the smoothing filter</td></tr>
51  <tr><td>@b `_humanoid_sink/filter/smoothing/confidence`</td><td>float64</td><td>undefined</td><td>The strength of the confidence component of the smoothing filter</td></tr>
52  <tr><td>@b `_humanoid_sink/filter/smoothing/window`</td><td>float64</td><td>undefined</td><td>The window (duration) of the smoothing filter; @c 0 = use all samples</td></tr>
53  </table>
54 
55  @return The requested semio::HumanoidSink
56  */
57  HumanoidSink::Ptr getHumanoidSink( std::string const & sink = "param" );
58 };
59 
60 }
61 
62 }
63 #endif // _SEMIO_ROS_HUMANOIDSINKADAPTER_H_
decltype(std::make_shared< HumanoidSink >()) typedef Ptr
Utility class to simplify the creation of semio::HumanoidSink instances.
::ros::NodeHandle _nh_rel
NodeHandle copy for interfacing with ROS.
HumanoidSinkAdapter(::ros::NodeHandle const &nh_rel, std::string const &default_sink="ros")
std::string _default_sink
The type of sink to use by default if param mode is selected and the ROS param _humanoid_sink/type is...
HumanoidSink::Ptr getHumanoidSink(std::string const &sink="param")
Create a semio::HumanoidSink.