Commit 4f3a9341 authored by ILIAD build farm's avatar ILIAD build farm
Browse files
parents 2c7ce6eb 21012be8
......@@ -3,10 +3,12 @@
<!-- Start rosbag with launchfile-->
<arg name="run_bag" default="false" />
<arg name="publish_map" default="false" />
<!-- Absolute Path to map to be used for localization. The map needs to be built by graph_fuser package -->
<arg name="map_file_path" default="$(find graph_map)/maps/ndt_map.MAP" />
<arg name="robot_prefix" default="robot5" />
<arg name="rviz_enabled" default="false" />
<arg name="root_id" default="/map_laser2d" />
<!-- Include visualization in rviz -->
<group if="$(arg rviz_enabled)">
......@@ -45,15 +47,16 @@
<param name="pose_init_t" value="0" />
<!-- world frame id -->
<param name="root_tf" value="world" />
<param name="root_tf" value="$(arg root_id)" />
<!-- odometry frame id-->
<param name="odom_tf" value="$(arg robot_prefix)/odom" />
<param name="base_tf" value="$(arg robot_prefix)/base_footprint" />
<!--param name="mcl_tf" value="mcl_pose_est" /-->
<!-- MCL parameters -->
<!-- MCL parameters -->
<param name="enable_localisation" value="true" />
<param name="resolution_local_factor" value="1.3" />
<param name="particle_count" value="500" />
......@@ -63,17 +66,19 @@
<param name="z_filter_height" value="1.0" />
</node>
<node name="occupancy_map_server" pkg="map_server" type="map_server" args=" $(find graph_map)/maps/occupancy_map.yaml" output="screen">
<remap from="/map" to="/maps/map_laser2d"/>
<node name="occupancy_map_server" pkg="map_server" type="map_server" args=" $(find graph_map)/maps/ncfm.yaml" output="screen" if="$(arg publish_map)">
<remap from="/map" to="/maps/map_laser2d"/>
<param name="~frame_id" value="map_laser2d"/>
</node>
<group if="$(arg rviz_enabled)">
<node name="graph_map_publisher" pkg="graph_map" type="graph_map_publisher" output="screen">
<param name="map_rate" value="1" />
<param name="map_file" value="$(arg map_file_path)" />
<param name="map_frame" value="/maps/map_2d_laser" />
<param name="map_parent_frame_id" value="/world" />
<param name="map_topic" value="/maps/map_2d_laser" />
<param name="map_frame" value="/maps/map_laser2d" />
<param name="map_parent_frame_id" value="$(arg root_id)" />
<param name="map_topic" value="/maps/map_laser2d" />
</node>
</group>
......@@ -82,7 +87,11 @@
<arg name="file_1" default="2018-05-18-09-55-16.bag" />
<node pkg="rosbag" type="play" name="player" output="screen" args="--clock -r 1.0 -q $(arg path)$(arg file_1)"/>
</group>
<node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_velodyne 100" />
<node pkg="tf" type="static_transform_publisher" name="occupancy_map_static_broadcaster" args="0 0 0 0 0 0 world map 100" />
<!-- node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_velodyne 100" / -->
<!-- node pkg="tf" type="static_transform_publisher" name="occupancy_map_static_broadcaster" args="0 0 0 0 0 0 world map 100" / -->
</launch>
<?xml version="1.0"?>
<launch>
<!-- Start rosbag with launchfile-->
<arg name="run_bag" default="false" />
<!-- Absolute Path to map to be used for localization. The map needs to be built by graph_fuser package -->
<arg name="map_file_path" default="$(find graph_map)/maps/ndt_map.MAP" />
<arg name="robot_prefix" default="robot5" />
<arg name="rviz_enabled" default="true" />
<arg name="root_link_id" default="map_laser2d" />
<!-- Include visualization in rviz -->
<group if="$(arg rviz_enabled)">
<include file="$(find graph_map)/launch/visualize_graph_fuser.launch" >
<arg name="localization" value="true" />
<arg name="oru-lab" value="true" />
</include>
</group>
<!-- Run monte carlo localization -->
<!--node name="occupancy_map_server" pkg="map_server" type="map_server" args=" $(find graph_map)/maps/occupancy_map.yaml" output="screen"/--> <!--frame_id map_velodyne-->
<group if="$(arg rviz_enabled)">
<node name="graph_map_publisher" pkg="graph_map" type="graph_map_publisher" output="screen">
<param name="map_rate" value="1" />
<param name="map_file" value="$(arg map_file_path)" />
<param name="map_frame" value="/maps/map_laser2d" />
<param name="map_parent_frame_id" value="$(arg root_link_id)"/>
<param name="map_topic" value="/maps/map_velodyne" />
</node>
</group>
<!--node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_velodyne 100"/-->
<!--node pkg="tf" type="static_transform_publisher" name="occupancy_map_static_broadcaster" args="0 0 0 0 0 0 world map 100"/-->
</launch>
......@@ -11,9 +11,12 @@ Panels:
- /Odometry1/Shape1
- /Odometry2/Shape1
- /Odometry3/Shape1
- /PoseArray1
- /Odometry4/Shape1
- /PointCloud21
- /PointCloud21/Autocompute Value Bounds1
- /NDT1
- /Map1
Splitter Ratio: 0.5
Tree Height: 815
- Class: rviz/Selection
......@@ -35,7 +38,7 @@ Panels:
Experimental: false
Name: Time
SyncMode: 0
SyncSource: PointCloud2
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
......@@ -62,63 +65,71 @@ Visualization Manager:
Frame Timeout: 15
Frames:
All Enabled: false
map:
asus_fork_depth_frame:
Value: true
map_velodyne:
asus_fork_depth_optical_frame:
Value: true
robot4/base_footprint:
asus_fork_link:
Value: true
robot4/base_fork:
asus_fork_rgb_frame:
Value: true
robot4/base_link:
asus_fork_rgb_optical_frame:
Value: true
robot4/base_link_ground_truth:
map_laser2d:
Value: true
robot4/camera_depth_frame:
robot5/asus_fork_base_link:
Value: true
robot4/camera_depth_optical_frame:
robot5/asus_fork_depth_optical_frame:
Value: true
robot4/camera_link:
robot5/asus_fork_link:
Value: true
robot4/camera_rgb_frame:
robot5/asus_fork_rgb_optical_frame:
Value: true
robot4/camera_rgb_optical_frame:
robot5/base_footprint:
Value: true
robot4/fixed_left_wheel_link:
robot5/base_footprint_ground_truth:
Value: true
robot4/fixed_right_wheel_link:
robot5/base_fork:
Value: true
robot4/kinect2_depth_optical_frame:
robot5/base_link:
Value: true
robot4/kinect2_ir_optical_frame:
robot5/fixed_left_wheel_link:
Value: true
robot4/kinect2_link:
robot5/fixed_right_wheel_link:
Value: true
robot4/kinect2_rgb_optical_frame:
robot5/kinect2_base_link:
Value: true
robot4/kinect_link:
robot5/kinect2_depth_optical_frame:
Value: true
robot4/laser2d_floor:
robot5/kinect2_ir_optical_frame:
Value: true
robot4/laser2d_floor_link:
robot5/kinect2_link:
Value: true
robot4/laser2d_top:
robot5/kinect2_rgb_optical_frame:
Value: true
robot4/laser2d_top_link:
robot5/laser2d_floor_base_link:
Value: true
robot4/left_fork:
robot5/laser2d_floor_link:
Value: true
robot4/odom:
robot5/laser2d_top_base_link:
Value: true
robot4/right_fork:
robot5/laser2d_top_link:
Value: true
robot4/robot4/velodyne:
robot5/left_fork:
Value: true
robot4/robot4/velodyne_base_link:
robot5/odom:
Value: true
robot4/sd_wheel_link:
robot5/right_fork:
Value: true
robot4/steer_link:
robot5/sd_wheel_link:
Value: true
robot5/steer_link:
Value: true
robot5/velodyne:
Value: true
robot5/velodyne_base_link:
Value: true
robot5/velodyne_link:
Value: true
submap_node0:
Value: true
......@@ -132,49 +143,52 @@ Visualization Manager:
Show Axes: true
Show Names: true
Tree:
world:
map:
{}
map_velodyne:
{}
robot4/odom:
robot4/base_footprint:
robot4/base_link:
robot4/base_fork:
robot4/left_fork:
map_laser2d:
robot5/odom:
robot5/base_footprint:
robot5/base_link:
robot5/asus_fork_base_link:
robot5/asus_fork_link:
robot5/asus_fork_depth_optical_frame:
{}
robot5/asus_fork_rgb_optical_frame:
{}
robot5/base_fork:
robot5/left_fork:
{}
robot4/right_fork:
robot5/right_fork:
{}
robot4/fixed_left_wheel_link:
robot5/fixed_left_wheel_link:
{}
robot4/fixed_right_wheel_link:
robot5/fixed_right_wheel_link:
{}
robot4/kinect2_link:
robot4/kinect2_depth_optical_frame:
{}
robot4/kinect2_rgb_optical_frame:
robot4/kinect2_ir_optical_frame:
robot5/kinect2_base_link:
robot5/kinect2_link:
robot5/kinect2_depth_optical_frame:
{}
robot4/kinect_link:
{}
robot4/laser2d_floor:
{}
robot4/laser2d_floor_link:
{}
robot4/laser2d_top:
{}
robot4/laser2d_top_link:
{}
robot4/robot4/velodyne_base_link:
robot4/robot4/velodyne:
robot5/kinect2_rgb_optical_frame:
robot5/kinect2_ir_optical_frame:
{}
robot5/laser2d_floor_base_link:
robot5/laser2d_floor_link:
{}
robot4/steer_link:
robot4/sd_wheel_link:
robot5/laser2d_top_base_link:
robot5/laser2d_top_link:
{}
robot5/steer_link:
robot5/sd_wheel_link:
{}
robot5/velodyne_base_link:
robot5/velodyne_link:
robot5/velodyne:
{}
velodyne:
{}
submap_node0:
{}
world:
robot5/base_footprint_ground_truth:
{}
Update Interval: 0
Value: true
- Class: rviz/MarkerArray
......@@ -337,7 +351,7 @@ Visualization Manager:
Topic: /ndt_mcl_pose
Unreliable: false
Value: true
- Alpha: 0.800000012
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 5.9265604
......@@ -348,7 +362,7 @@ Visualization Manager:
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: AxisColor
Decay Time: 10
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
......@@ -359,7 +373,7 @@ Visualization Manager:
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 1
Size (Pixels): 3
Size (m): 0.0500000007
Style: Points
Topic: /cloud_localized
......@@ -390,7 +404,7 @@ Visualization Manager:
Global Options:
Background Color: 130; 130; 130
Default Light: true
Fixed Frame: world
Fixed Frame: map_laser2d
Frame Rate: 70
Name: root
Tools:
......@@ -411,25 +425,25 @@ Visualization Manager:
Views:
Current:
Class: rviz/XYOrbit
Distance: 18.1015873
Distance: 66.5617294
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: -3.50539112
Y: -25.8522511
Z: 5.3598078e-06
X: 7.46893883
Y: -6.24155045
Z: 1.15941584e-05
Focal Shape Fixed Size: false
Focal Shape Size: 0.0500000007
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: -0.0452038944
Pitch: 1.25979626
Target Frame: world
Value: XYOrbit (rviz)
Yaw: 0.784042537
Yaw: 6.12041521
Saved:
- Class: rviz/Orbit
Distance: 39.1665726
......@@ -457,7 +471,7 @@ Window Geometry:
Height: 1028
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd0000000400000000000001aa000003befc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003be000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003befc0200000003fb0000000a005600690065007700730100000028000003be000000ad00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000064f000000b0fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006500000000000000073f0000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000047a000003be00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
QMainWindow State: 000000ff00000000fd0000000400000000000002a7000003befc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000003be000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000003befc0200000003fb0000000a005600690065007700730100000028000003be000000ad00fffffffb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b20000000000000000000000020000064f000000b0fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006500000000000000073f0000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000037d000003be00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
......
......@@ -176,8 +176,8 @@ bool MCLNDTType::UpdateAndPredict(pcl::PointCloud<pcl::PointXYZ> &cloud, const E
Eigen::Affine3d Tlast=graph_map_->GetCurrentNodePose()*pf.getMean();
bool disable_prediciton_noise=false; // if there os
if( (Tlast.translation()-pose_last_update_.translation()).norm()<0.01 && (pose_last_update_.inverse()*Tlast).rotation().eulerAngles(0,1,2).norm()<0.005 )
disable_prediciton_noise=true;
//if( (Tlast.translation()-pose_last_update_.translation()).norm()<0.01 && (pose_last_update_.inverse()*Tlast).rotation().eulerAngles(0,1,2).norm()<0.005 )
// disable_prediciton_noise=true;
OdometryPrediction(Tmotion,disable_prediciton_noise);
Eigen::Affine3d Tinit=graph_map_->GetCurrentNodePose()*pf.getMean();
......
......@@ -167,9 +167,8 @@ class localisation_node {
tf::poseMsgToEigen(pose_init,pose_init_eig);
cout<<"Initial position set to"<<pose_init_eig.translation().transpose()<<endl;
Vector6d var;
var<<0.5, 0.5, 0.0, 0.0, 0.0, 0.2;
var<<1.0, 1.0, 0.0, 0.0, 0.0, 0.5;
localisation_type_ptr_->InitializeLocalization(pose_init_eig,var);
sleep(1);
initialized=true;
}
void InitializeUniform(const geometry_msgs::Pose &pose_init,const ros::Time &t_init){
......@@ -235,16 +234,15 @@ class localisation_node {
Initialize(pose_init_geom, ts);
}
tf::StampedTransform transform;
double x, y, yaw;
//double x, y, yaw;
tf_listener.waitForTransform(odomTF, baseTF, ts, ros::Duration(0.1));
try{
tf_listener.lookupTransform(odomTF, baseTF,/*ros::Time(0)*/ts, transform);
yaw = tf::getYaw(transform.getRotation());
/* yaw = tf::getYaw(transform.getRotation());
x = transform.getOrigin().x();
y = transform.getOrigin().y();
y = transform.getOrigin().y();*/
}
catch(tf::TransformException ex){
ROS_ERROR("%s", ex.what());
......
......@@ -44,6 +44,8 @@ public:
void PlotActiveNodesCloud();
void SetParentFrameId(const std::string &parent_frame_id){parent_frame_id_=parent_frame_id;}
void PlotAllClouds();
void PlotLinks(ros::Time t=ros::Time::now());
......@@ -72,6 +74,7 @@ void PlotGraphThread();
std::string tf_prefix_="/tf";
ros::NodeHandle nh_;
GraphMapNavigatorPtr graph_map_;
std::string parent_frame_id_="/world";
bool visualization_enabled_=false;
bool visualize_map_=false;
......
<?xml version="1.0" encoding="utf-8"?>
<launch>
<arg name="run_bag" default="false"/>
<arg name="robot_prefix" default="robot5"/>
<arg name="output_pointcloud_topic_name" default="/fused_cloud"/>
<arg name="rviz_enabled" default="false"/>
<group if="$(arg rviz_enabled)">
<!-- Include visualization in rviz -->
<include file="$(find graph_map)/launch/visualize_graph_fuser.launch" >
<arg name="mapping" value="true" />
<arg name="oru-lab" value="true" />
</include>
</group>
<!-- start mapping node -->
<node pkg="graph_map" type="graph_map_fuser_node" name="graph_node" output="screen">
<!-- Choose weather to initiate pose to pose_init_<x,y,t> or the data of /<gt_topic> -->
<param name="initPoseFromGT" value="false" />
<param name="pose_init_x" value="0" />
<param name="pose_init_y" value="0" />
<param name="pose_init_t" value="0" />
<param name="save_occupancy" value="true" />
<!-- Select mapping technique to one of the methods listed in graph_map/include/graph_factory.h -->
<param name="map_type" value="ndt_map" />
<!-- use local maps instead of a single map, this can improve map descriptiveness -->
<param name="use_submap" value="false" />
<param name="interchange_radius" value="7" />
<param name="compound_radius" value="0" />
<param name="map_switching_method" value="node_position_esg" /> <!-- <node_position> (revisit previously mapped nodes), node_position_est (never revisit, form an exactly sparse submap graph -->
<param name="velodyne_config_file" value="$(find graph_map)/config/VLP16db.yaml" />
<!-- choose to disable essential parts of the software -->
<param name="enable_registration" value="true" />
<param name="registration_2D" value="false" />
<!-- Select registration technique to one of the methods listed in graph_map/include/graph_factory.h -->
<param name="registration_type" value="ndt_d2d_reg" />
<!-- Use fine to course ndt_cells in registration -->
<param name="multi-res" value="false" />
<param name="resolutionLocalFactor" value="1.2" />
<param name="reg_itr_max" value="30" />
<!-- Resolution of a map, usually between 0.4 and 1.2 -->
<param name="n_neighbours" value="1" />
<param name="enable_mapping" value="true" />
<param name="resolution" value="0.65" />
<param name="tf_pose_frame" value="" />
<!-- if laser_2d is true, a 2d scanner will be used for mapping-->
<param name="laser_2d" value="false" />
<param name="laser_frame_id" value="$(arg robot_prefix)/velodyne " />
<!-- Topic of laser scanner -->
<!--param name="points_topic" value="$(arg namespace_prefix)/kmo_navserver/laserscan1" /-->
<param name="points_topic" value="$(arg robot_prefix)/sensors/velodyne_packets" />
<param name="output_pointcloud_topic_name" value="$(arg output_pointcloud_topic_name)" />
<param name="useOdometry" value="true" />
<param name="odometry_topic" value="$(arg robot_prefix)/control/odom"/>
<param name="use_tf_listener" value="true" />
<param name="gt_topic" value="$(arg robot_prefix)/control/state" />
<!-- odometry frame id-->
<param name="odom_tf" value="$(arg robot_prefix)/odom" />
<param name="base_tf" value="$(arg robot_prefix)/base_footprint" />
<!-- check if the registration pose output is similar to odometry prediction within max_translation_norm or max_rotation_norm -->
<param name="check_consistency" value="true" />
<param name="max_translation_norm" value="0.2" />
<param name="max_rotation_norm" value="0.78539816339" />
<!-- size of map -->
<param name="size_x_meters" value="70" />
<param name="size_y_meters" value="70" />
<param name="size_z_meters" value="10" />
<!--<param name="laser_variance_z" value="0.02" /> -->
<!--range of sensor, min range can prevent self-mapping of the robot or operator of the lidar, max range can remove uncertain measurments -->
<param name="max_range" value="130." />
<param name="min_range" value="1.8" />
<!-- Specific sensor offset parameters with respect to the odometry frame -->
<param name="sensor_pose_x" value="0.807" />
<param name="sensor_pose_y" value="-0.003" />
<param name="sensor_pose_z" value="0.95" />
<param name="sensor_pose_t" value="0" />
<param name="sensor_offset_t" value="0.0" />
<!-- Output directory where the map is stored -->
<!-- invoke rosservice call /graph_ -->
<param name="map_directory" value="$(find graph_map)/maps" />
<param name="visualize" value="true" />
<param name="disable_map_visualization" value="false" />
<param name="T_map" value="3.0" />
<!-- a minimum movement is required before fusing frames -->
<param name="use_keyframe" value="true" />
<param name="min_keyframe_dist" value="0.05" />
<param name="min_keyframe_rot_deg" value="1.0" />
</node>
<node pkg="octomap_server" type="octomap_server_node" name="octomap_server">
<remap from="cloud_in" to="$(arg output_pointcloud_topic_name)"/>
<param name="frame_id" value="world"/>
<param name="resolution" value="0.15"/>
<param name="sensor_model/max_range" value="10.0"/>
<param name="pointcloud_max_z" value="5"/>
<param name="occupancy_min_z" value="0.1"/>
<param name="occupancy_max_z" value="1.8"/>
</node>
<!-- start a rosbag -->
<group if="$(arg run_bag)">
<arg name="path" default="$(find graph_map)/data/" />
<arg name="file_1" default="2018-05-18-09-55-16.bag" />
<node pkg="rosbag" type="play" name="player" output="screen" args="--clock -r 1.0 -q $(arg path)$(arg file_1)"/>
</group>
<node pkg="tf" type="static_transform_publisher" name="velodyne_map_static_broadcaster" args="0 0 0 0 0 0 world map_laser2d 100" />
</launch>
......@@ -8,7 +8,7 @@
<param name="file_name" value="$(arg file_name)"/>
</node-->
<!--node pkg="rviz" type="rviz" name="rviz" args="-d $(find graph_map)/rviz/showMap.rviz" /-->
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 world map_velodyne 100" />
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 world map 100" />
</launch>
......
<?xml version="1.0" encoding="utf-8"?>
<launch>
<arg name="run_bag" default="false"/>
<arg name="robot_prefix" default="robot5"/>
<arg name="output_pointcloud_topic_name" default="/fused_cloud"/>
<arg name="rviz_enabled" default="true"/>
<group if="$(arg rviz_enabled)">
<!-- Include visualization in rviz -->
<include file="$(find graph_map)/launch/visualize_graph_fuser.launch" >
<arg name="mapping" value="true" /> Command 'rosbag' from package 'python-rosbag' (universe)
<arg name="oru-lab" value="true" />
</include>
</group>