semio_ros  0.10.6
semio::ros::HumanoidSinkAdapter Class Reference

Utility class to simplify the creation of semio::HumanoidSink instances. More...

#include <semio/ros/humanoid_sink_adapter.h>

Public Member Functions

 HumanoidSinkAdapter (::ros::NodeHandle const &nh_rel, std::string const &default_sink="ros")
 
HumanoidSink::Ptr getHumanoidSink (std::string const &sink="param")
 Create a semio::HumanoidSink. More...
 

Protected Attributes

::ros::NodeHandle _nh_rel
 NodeHandle copy for interfacing with ROS. More...
 
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 not defined. More...
 

Detailed Description

Utility class to simplify the creation of semio::HumanoidSink instances.

Definition at line 15 of file humanoid_sink_adapter.h.

Constructor & Destructor Documentation

semio::ros::HumanoidSinkAdapter::HumanoidSinkAdapter ( ::ros::NodeHandle const &  nh_rel,
std::string const &  default_sink = "ros" 
)
Parameters
nh_relNodeHandle copy for interfacing with ROS.
default_sinkThe type of sink to use by default if param mode is selected and the ROS param _humanoid_sink/type is not defined.

Definition at line 5 of file humanoid_sink_adapter.cpp.

Member Function Documentation

semio::HumanoidSink::Ptr semio::ros::HumanoidSinkAdapter::getHumanoidSink ( std::string const &  sink = "param")

Create a semio::HumanoidSink.

If the ROS param _humanoid_sink/filter/smoothing is defined, then a semio::HumanoidSmoothingFilter will be added to the sink's filter list. See ROS Params for more info.

Parameters
sinkThe type of sink to create
ValueResulting pointer typeNotes
"param"variable based on ROS paramUses the value of the ROS param _humanoid_sink/type to set sink; defaults to _default_sink defined during construction
"ros"semio::ros::HumanoidSinkROSUse ROS to sink humanoids; if the smoothing filter is enabled, creates the sink on topic ~humanoids/smoothed
"none"semio::ros::HumanoidSinkROSSpecialization of semio::ros::HumanoidSinkROS, connects to topic /null
Note
"none" will be used if the value of sink is not recognized

ROS Params
NameTypeDefaultDescription
_humanoid_sink/type string_default_sinkType of sink to create when sink is "param"
_humanoid_sink/filter/smoothing/add anyundefinedDefine this parameter to add a default smoothing filter to outgoing humanoids (when no other smoothing params are defined)
_humanoid_sink/filter/smoothing/position float64undefinedThe strength of the position component of the smoothing filter
_humanoid_sink/filter/smoothing/orientation float64undefinedThe strength of the orientation component of the smoothing filter
_humanoid_sink/filter/smoothing/confidence float64undefinedThe strength of the confidence component of the smoothing filter
_humanoid_sink/filter/smoothing/window float64undefinedThe window (duration) of the smoothing filter; 0 = use all samples
Returns
The requested semio::HumanoidSink

Definition at line 13 of file humanoid_sink_adapter.cpp.

References _default_sink, _nh_rel, semio::HumanoidSmoothingFilter::getSmoothing(), semio::HumanoidStateFilter::getStandardFilterHumanoid(), and semio::HumanoidSink::Ptr.

Referenced by main().

+ Here is the call graph for this function:

+ Here is the caller graph for this function:

Field Documentation

std::string semio::ros::HumanoidSinkAdapter::_default_sink
protected

The type of sink to use by default if param mode is selected and the ROS param _humanoid_sink/type is not defined.

See also
getHumanoidSink()

Definition at line 21 of file humanoid_sink_adapter.h.

Referenced by getHumanoidSink().

::ros::NodeHandle semio::ros::HumanoidSinkAdapter::_nh_rel
protected

NodeHandle copy for interfacing with ROS.

Definition at line 19 of file humanoid_sink_adapter.h.

Referenced by getHumanoidSink().


The documentation for this class was generated from the following files: