最近在使用OpenPTrack
来进行人的跟踪测试,可是运行程序的时候总是崩溃。
OpenPTrack
是通过roslaunch
命令来运行程序的。
网上搜索了一下,可以找到对应的launch
文件,在其中的node
节点中增加如下语句即可
1 |
launch-prefix="xterm -e gdb -ex run --args " |
我们以
1 |
$ roslaunch tracking detection_and_tracking_kinect2.launch |
这条命令为例,detection_and_tracking_kinect2.launch
文件的原始内容如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 |
<launch> <arg name="camera_name" default="kinect2_head" /> <!-- Start the Kinect --> <include file="$(find kinect2_bridge)/launch/kinect2_bridge_ir.launch"/> <!-- Launch ground based people detection node --> <node pkg="detection" type="ground_based_people_detector" name="ground_based_people_detector" output="screen" required="true"> <rosparam command="load" file="$(find detection)/conf/ground_based_people_detector_kinect2.yaml" /> <param name="classifier_file" value="$(find detection)/data/HogSvmPCL.yaml"/> <!--param name="camera_info_topic" value="/$(arg camera_name)/depth_lowres/camera_info"/--> <param name="camera_info_topic" value="/$(arg camera_name)/ir_rect/camera_info"/> <param name="output_topic" value="/detector/detections"/> <!--param name="pointcloud_topic" value="/$(arg camera_name)/depth_lowres/points"/--> <param name="pointcloud_topic" value="/$(arg camera_name)/depth_ir/points"/> <param name="rate" value="60.0"/> </node> </launch> |
增加调试命令之后的样子如下:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 |
<launch> <arg name="camera_name" default="kinect2_head" /> <!-- Start the Kinect --> <include file="$(find kinect2_bridge)/launch/kinect2_bridge_ir.launch"/> <!-- Launch ground based people detection node --> <node pkg="detection" type="ground_based_people_detector" name="ground_based_people_detector" output="screen" required="true" launch-prefix="xterm -e gdb -ex run --args "> <rosparam command="load" file="$(find detection)/conf/ground_based_people_detector_kinect2.yaml" /> <param name="classifier_file" value="$(find detection)/data/HogSvmPCL.yaml"/> <!--param name="camera_info_topic" value="/$(arg camera_name)/depth_lowres/camera_info"/--> <param name="camera_info_topic" value="/$(arg camera_name)/ir_rect/camera_info"/> <param name="output_topic" value="/detector/detections"/> <!--param name="pointcloud_topic" value="/$(arg camera_name)/depth_lowres/points"/--> <param name="pointcloud_topic" value="/$(arg camera_name)/depth_ir/points"/> <param name="rate" value="60.0"/> </node> </launch> |
(注意代码添加位置)这样在执行原来例子的时候,就会先打开一个新的Shell
界面,被调试的程序就在这个Shell
中被执行了。
如果被调式的是Python
脚本,则需要修改调试器为pdb
,如下:
1 |
launch-prefix="xterm -e python -m pdb " |