Running the Driver

You can run Bebop’s ROS drivereither as a ROS Nodelet or as a standalone ROS Node. The former is recommended if you intend to perform any kind of processing on Bebop’s video stream.

Note

If you compile the driver form source, do not forget to source your catkin workspace prior to running the driver. (i.e. source ~/bebop_ws/devel/setup.[bash|zsh])

Note

Ensure that your Bebop’s firmware is at least 2.0.29 and your computer is connected to Bebop’s wireless network.

Running the driver as a Node

The executable node is called bebop_driver_node and exists in bebop_driver package. It’s recommended to run the Node in its own namespace and with default configuration. The driver package comes with a sample launch file bebop_driver/launch/bebop_node.launch which demonstrates the procedure.

$ roslaunch bebop_driver bebop_node.launch
bebop_node.launch
<?xml version="1.0"?>
<launch>
    <arg name="namespace" default="bebop" />
    <arg name="ip" default="192.168.42.1" />
    <arg name="config_file" default="$(find bebop_driver)/config/defaults.yaml" />
    <arg name="camera_info_url" default="package://bebop_driver/data/bebop_camera_calib.yaml" />
    <group ns="$(arg namespace)">
        <node pkg="bebop_driver" name="bebop_driver" type="bebop_driver_node" output="screen">
            <param name="camera_info_url" value="$(arg camera_info_url)" />
            <param name="bebop_ip" value="$(arg ip)" />
            <rosparam command="load" file="$(arg config_file)" />
        </node>
        <include file="$(find bebop_description)/launch/description.launch" />
    </group>
</launch>

Running the driver as a Nodelet

To run the driver as a ROS Nodelet, you need to first run a Nodelet manager, then load the driver’s Nodelet (bebop_driver/BebopDriverNodelet) in it, along with other Nodelets that need to communicate with the driver. bebop_tools/launch/bebop_nodelet_iv.launch is a sample launch file that demonstrates these steps by visualizing Bebop’s video stream using an instance of image_view/image Nodelet. Similar to bebop_node.launch, it also runs everything in its own namespace and loads the default configuration.

$ roslaunch bebop_tools bebop_nodelet_iv.launch
bebop_tools/launch/bebop_nodelet_iv.launch
<?xml version="1.0"?>
<launch>
    <!-- include the nodelet launch file from bebop_driver -->
    <arg name="namespace" default="bebop" />
    <include file="$(find bebop_driver)/launch/bebop_nodelet.launch">
      <arg name="namespace" value="$(arg namespace)" />
    </include>
    <!-- use the same nodelet manager and namespace, then load image_view nodelet -->
    <group ns="$(arg namespace)">
       <node pkg="nodelet" type="nodelet" name="bebop_image_view_nodelet"
          args="load image_view/image bebop_nodelet_manager">
          <remap from="image" to="image_raw" />
        </node>
    </group>
</launch>
bebop_driver/launch/bebop_nodelet.launch
<?xml version="1.0"?>
<launch>
    <arg name="namespace" default="bebop" />
    <arg name="ip" default="192.168.42.1" />
    <arg name="config_file" default="$(find bebop_driver)/config/defaults.yaml" />
    <arg name="camera_info_url" default="package://bebop_driver/data/bebop_camera_calib.yaml" />
    <group ns="$(arg namespace)">
        <!-- nodelet manager -->
        <node pkg="nodelet" type="nodelet" name="bebop_nodelet_manager" args="manager" output="screen"/>
        <!-- bebop_nodelet -->
        <node pkg="nodelet" type="nodelet" name="bebop_nodelet"
          args="load bebop_driver/BebopDriverNodelet bebop_nodelet_manager">
            <param name="camera_info_url" value="$(arg camera_info_url)" />
            <param name="bebop_ip" value="$(arg ip)" />
            <rosparam command="load" file="$(arg config_file)" />
        </node>
        <include file="$(find bebop_description)/launch/description.launch" />
    </group>
</launch>