semio_ros  0.10.6
humanoid_source_adapter.h
Go to the documentation of this file.
1 #ifndef _SEMIO_ROS_HUMANOIDSOURCEADAPTER_H_
2 #define _SEMIO_ROS_HUMANOIDSOURCEADAPTER_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::HumanoidSource instances
16 {
17 protected:
18  //! NodeHandle copy for interfacing with ROS
19  ::ros::NodeHandle _nh_rel;
20  //! The type of source to use by default if param mode is selected and the ROS param @b `_humanoid_source/type` is not defined @sa getHumanoidSource()
21  std::string _default_source;
22 
23 public:
24  /**
25  @param nh_rel @copybrief _nh_rel
26  @param default_source @copybrief _default_source
27  */
28  HumanoidSourceAdapter( ::ros::NodeHandle const & nh_rel, std::string const & default_source = "fullbody" );
29 
30  //! Create a semio::HumanoidSource
31  /**
32  If the ROS param @b `_humanoid_source/filter/smoothing` is defined, then a semio::HumanoidSmoothingFilter will be added to the source's filter list. See @ref getHumanoidSource-ros-params "ROS Params" for more info.
33 
34  @param source The type of source 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_source/type` to set @p source; defaults to #_default_source defined during construction</td></tr>
38  <tr><td>`"nite"`</td><td>semio::HumanoidSourceNiTE</td><td>Use Kinect V2/NiTE to source humanoids (full body, only rough head pose)</td></tr>
39  <tr><td>`"openface"`</td><td>semio::HumanoidSourceOpenFace</td><td>Use OpenFace to source humanoids (head pose only)</td></tr>
40  <tr><td>`"fullbody"`</td><td>semio::HumanoidSourceFullBody</td><td>Merge humanoids from Kinect V2/NiTE and OpenFace (full body, including head)</td></tr>
41  <tr><td>`"ros"`</td><td>semio::ros::HumanoidSourceROS</td><td>Use ROS to source humanoids</td></tr>
42  <tr><td>`"none"`</td><td>semio::ros::HumanoidSourceROS</td><td>Specialization of semio::ros::HumanoidSourceROS, connects to topic @b `/null`</td></tr>
43  <tr><td>`"virtual"`</td><td>semio::ros::HumanoidSourceVirtual</td><td>Create virtual humanoid that can be posed in code</td></tr>
44  </table>
45  @note `"none"` will be used if the value of @p source is not recognized
46 
47  @anchor getHumanoidSource-ros-params
48  @par ROS Params
49  <table>
50  <tr><th>Name</th><th>Type</th><th>Default</th><th>Description</th></tr>
51  <tr><td>@b `_humanoid_source/type`</td><td>string</td><td>#_default_source</td><td>Type of source to create when @p source is `"param"`</td></tr>
52  <tr><td>@b `_humanoid_source/filter/smoothing/add`</td><td>any</td><td>undefined</td><td>Define this parameter to add a default smoothing filter to incoming humanoids (when no other smoothing params are defined)</td></tr>
53  <tr><td>@b `_humanoid_source/filter/smoothing/position`</td><td>float64</td><td>undefined</td><td>The strength of the position component of the smoothing filter</td></tr>
54  <tr><td>@b `_humanoid_source/filter/smoothing/orientation`</td><td>float64</td><td>undefined</td><td>The strength of the orientation component of the smoothing filter</td></tr>
55  <tr><td>@b `_humanoid_source/filter/smoothing/confidence`</td><td>float64</td><td>undefined</td><td>The strength of the confidence component of the smoothing filter</td></tr>
56  <tr><td>@b `_humanoid_source/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>
57  <tr><td>@b `_humanoid_source/fullbody/show_cropped_image`</td><td>bool</td><td>false</td><td>Whether to display the cropped face image from semio::HumanoidSourceFullBody</td></tr>
58  </table>
59 
60  @return The requested semio::HumanoidSource
61  */
62  HumanoidSource::Ptr getHumanoidSource( std::string const & source = "param" );
63 };
64 
65 }
66 
67 }
68 
69 #endif // _SEMIO_ROS_HUMANOIDSOURCEADAPTER_H_
HumanoidSourceAdapter(::ros::NodeHandle const &nh_rel, std::string const &default_source="fullbody")
::ros::NodeHandle _nh_rel
NodeHandle copy for interfacing with ROS.
std::string _default_source
The type of source to use by default if param mode is selected and the ROS param _humanoid_source/typ...
decltype(std::make_shared< HumanoidSource >()) typedef Ptr
Utility class to simplify the creation of semio::HumanoidSource instances.
HumanoidSource::Ptr getHumanoidSource(std::string const &source="param")
Create a semio::HumanoidSource.