ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
In addition to @Dan Lazewatsky's through answer, I summarized what I found out for some argument names in launch files in pkg's wiki page. I had to correct the topic names at arg
s in a launch file.
As a record I paste what works for me with camera output from roslaunch turtlebot_gazebo turtlebot_world.launch
.
<launch>
<arg name="camera" default="camera" />
<arg name="depth_ns" default="depth" />
<arg name="image_topic" default="image_raw" />
<arg name="depth_topic" default="image_raw" />
<arg name="fixed_frame" default="/camera_rgb_frame" />
<!--include file="$(find openni_launch)/launch/openni.launch"/-->
<node name="$(anon dynparam)" pkg="dynamic_reconfigure" type="dynparam" args="set_from_parameters $(arg camera)/driver">
<param name="depth_registration" type="bool" value="true" />
</node>
<node pkg="face_detector" type="face_detector" name="face_detector" output="screen">
<remap from="camera" to="$(arg camera)" />
<remap from="image_topic" to="$(arg image_topic)" />
<remap from="depth_topic" to="$(arg depth_topic)" />
<remap from="depth_ns" to="$(arg depth_ns)" />
<param name="fixed_frame" type="string" value="$(arg fixed_frame)" />
<param name="classifier_name" type="string" value="frontalface" />
<rosparam command="load" file="$(find face_detector)/param/classifier.yaml"/>
<param name="classifier_reliability" type="double" value="0.9"/>
<param name="do_continuous" type="bool" value="true" />
<param name="do_publish_faces_of_unknown_size" type="bool" value="false" />
<param name="do_display" type="bool" value="false" />
<param name="use_rgbd" type="bool" value="true" />
<param name="approximate_sync" type="bool" value="true" />
</node>
</launch>
Topics I was getting from turtlebot Gazebo.
$ rosnode info /face_detector
--------------------------------------------------------------------------------
Node [/face_detector]
Publications:
* /face_detector/result [face_detector/FaceDetectorActionResult]
* /face_detector/status [actionlib_msgs/GoalStatusArray]
* /face_detector/faces_cloud [sensor_msgs/PointCloud]
* /face_detector/people_tracker_measurements_array [people_msgs/PositionMeasurementArray]
* /rosout [rosgraph_msgs/Log]
* /face_detector/feedback [face_detector/FaceDetectorActionFeedback]
Subscriptions:
* /camera/rgb/image_raw [sensor_msgs/Image]
* /tf [tf2_msgs/TFMessage]
* /camera/depth/camera_info [sensor_msgs/CameraInfo]
* /tf_static [unknown type]
* /face_detector/cancel [unknown type]
* /camera/rgb/camera_info [sensor_msgs/CameraInfo]
* /face_detector/goal [unknown type]
* /camera/depth/image_raw [sensor_msgs/Image]
* /clock [rosgraph_msgs/Clock]
2 | No.2 Revision |
In addition to @Dan Lazewatsky's through answer, I summarized what I found out for some argument names in launch files in pkg's wiki page. I had to correct the topic names at arg
s in a launch file.
As a record I paste what works for me with camera output from roslaunch turtlebot_gazebo turtlebot_world.launch
. (I used this human model on Gazebo).
<launch>
<arg name="camera" default="camera" />
<arg name="depth_ns" default="depth" />
<arg name="image_topic" default="image_raw" />
<arg name="depth_topic" default="image_raw" />
<arg name="fixed_frame" default="/camera_rgb_frame" />
<!--include file="$(find openni_launch)/launch/openni.launch"/-->
<node name="$(anon dynparam)" pkg="dynamic_reconfigure" type="dynparam" args="set_from_parameters $(arg camera)/driver">
<param name="depth_registration" type="bool" value="true" />
</node>
<node pkg="face_detector" type="face_detector" name="face_detector" output="screen">
<remap from="camera" to="$(arg camera)" />
<remap from="image_topic" to="$(arg image_topic)" />
<remap from="depth_topic" to="$(arg depth_topic)" />
<remap from="depth_ns" to="$(arg depth_ns)" />
<param name="fixed_frame" type="string" value="$(arg fixed_frame)" />
<param name="classifier_name" type="string" value="frontalface" />
<rosparam command="load" file="$(find face_detector)/param/classifier.yaml"/>
<param name="classifier_reliability" type="double" value="0.9"/>
<param name="do_continuous" type="bool" value="true" />
<param name="do_publish_faces_of_unknown_size" type="bool" value="false" />
<param name="do_display" type="bool" value="false" />
<param name="use_rgbd" type="bool" value="true" />
<param name="approximate_sync" type="bool" value="true" />
</node>
</launch>
Topics I was getting from turtlebot Gazebo.
$ rosnode info /face_detector
--------------------------------------------------------------------------------
Node [/face_detector]
Publications:
* /face_detector/result [face_detector/FaceDetectorActionResult]
* /face_detector/status [actionlib_msgs/GoalStatusArray]
* /face_detector/faces_cloud [sensor_msgs/PointCloud]
* /face_detector/people_tracker_measurements_array [people_msgs/PositionMeasurementArray]
* /rosout [rosgraph_msgs/Log]
* /face_detector/feedback [face_detector/FaceDetectorActionFeedback]
Subscriptions:
* /camera/rgb/image_raw [sensor_msgs/Image]
* /tf [tf2_msgs/TFMessage]
* /camera/depth/camera_info [sensor_msgs/CameraInfo]
* /tf_static [unknown type]
* /face_detector/cancel [unknown type]
* /camera/rgb/camera_info [sensor_msgs/CameraInfo]
* /face_detector/goal [unknown type]
* /camera/depth/image_raw [sensor_msgs/Image]
* /clock [rosgraph_msgs/Clock]
Result:
$ rostopic echo /face_detector/people_tracker_measurements_array
header:
seq: 202
stamp:
secs: 3317
nsecs: 190000000
frame_id: camera_depth_optical_frame
people:
-
header:
seq: 0
stamp:
secs: 3317
nsecs: 190000000
frame_id: camera_depth_optical_frame
name: frontalface
object_id: 3
pos:
x: -0.815850454715
y: -1.44855080735
z: 3.6913383007
reliability: 0.9
covariance: [0.04, 0.0, 0.0, 0.0, 0.04, 0.0, 0.0, 0.0, 0.04]
initialization: 1
cooccurrence: []