Skip to content

Commit

Permalink
Add bebop ip address as ROS parameter (fixes #19)
Browse files Browse the repository at this point in the history
- Param name: `bebop_ip`
- Set default ip (192.148.42.1) in launch files
  • Loading branch information
anuppari authored and mani-monaj committed Nov 24, 2015
1 parent 61239d4 commit 5bcdfb4
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 5 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -36,3 +36,6 @@ bebop_driver/scripts/meta/*.msg
bebop_driver/scripts/meta/*.h
bebop_driver/scripts/meta/*.cfg
bebop_driver/scripts/meta/*.rst

# Temporary files
*~
3 changes: 2 additions & 1 deletion bebop_driver/include/bebop_driver/bebop.h
Original file line number Diff line number Diff line change
Expand Up @@ -93,6 +93,7 @@ class Bebop
eARCONTROLLER_DEVICE_STATE device_state_;
ARSAL_Sem_t state_sem_;
boost::shared_ptr<VideoDecoder> video_decoder_ptr_;
std::string bebop_ip_;

// Navdata Callbacks
#define DEFINE_SHARED_PTRS
Expand Down Expand Up @@ -141,7 +142,7 @@ class Bebop
explicit Bebop(ARSAL_Print_Callback_t custom_print_callback = 0);
~Bebop();

void Connect(ros::NodeHandle& nh, ros::NodeHandle& priv_nh);
void Connect(ros::NodeHandle& nh, ros::NodeHandle& priv_nh, const std::string& bebop_ip = "192.168.42.1");
void StartStreaming();

// Disable all data callback and streaming (nothrow)
Expand Down
1 change: 1 addition & 0 deletions bebop_driver/launch/bebop_node.launch
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<group ns="bebop">
<node pkg="bebop_driver" name="bebop_driver" type="bebop_driver_node" output="screen">
<param name="camera_info_url" value="package://bebop_driver/data/bebop_camera_calib.yaml" />
<param name="bebop_ip" value="192.168.42.1" />
<rosparam command="load" file="$(find bebop_driver)/config/defaults.yaml" />
</node>
</group>
Expand Down
1 change: 1 addition & 0 deletions bebop_driver/launch/bebop_nodelet.launch
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
<node pkg="nodelet" type="nodelet" name="bebop_nodelet"
args="load bebop_driver/BebopDriverNodelet bebop_nodelet_manager">
<param name="camera_info_url" value="package://bebop_driver/data/bebop_camera_calib.yaml" />
<param name="bebop_ip" value="192.168.42.1" />
<rosparam command="load" file="$(find bebop_driver)/config/defaults.yaml" />
</node>
</group>
Expand Down
7 changes: 5 additions & 2 deletions bebop_driver/src/bebop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ Bebop::~Bebop()
if (device_controller_ptr_) ARCONTROLLER_Device_Delete(&device_controller_ptr_);
}

void Bebop::Connect(ros::NodeHandle& nh, ros::NodeHandle& priv_nh)
void Bebop::Connect(ros::NodeHandle& nh, ros::NodeHandle& priv_nh, const std::string& bebop_ip)
{
try
{
Expand All @@ -223,10 +223,13 @@ void Bebop::Connect(ros::NodeHandle& nh, ros::NodeHandle& priv_nh)
throw std::runtime_error("Discovery failed: " + std::string(ARDISCOVERY_Error_ToString(error_discovery)));
}

// set/save ip
bebop_ip_ = bebop_ip;

// TODO(mani-monaj): Make ip and port params
error_discovery = ARDISCOVERY_Device_InitWifi(device_ptr_,
ARDISCOVERY_PRODUCT_ARDRONE, "Bebop",
"192.168.42.1", 44444);
bebop_ip_.c_str(), 44444);

if (error_discovery != ARDISCOVERY_OK)
{
Expand Down
5 changes: 3 additions & 2 deletions bebop_driver/src/bebop_driver_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ int BebopPrintToROSLogCB(eARSAL_PRINT_LEVEL level, const char *tag, const char *
} // namespace util

BebopDriverNodelet::BebopDriverNodelet()
: bebop_ptr_(new bebop_driver::Bebop(util::BebopPrintToROSLogCB))
: bebop_ptr_(new bebop_driver::Bebop(util::BebopPrintToROSLogCB))
{
NODELET_INFO("Nodelet Cstr");
}
Expand All @@ -77,13 +77,14 @@ void BebopDriverNodelet::onInit()
// TODO(mani-monaj): Wrap all calls to .param() in a function call to enable logging
const bool param_reset_settings = private_nh.param("reset_settings", false);
const std::string& param_camera_info_url = private_nh.param<std::string>("camera_info_url", "");
const std::string& param_bebop_ip = private_nh.param<std::string>("bebop_ip", "192.168.42.1");

param_frame_id_ = private_nh.param<std::string>("camera_frame_id", "camera");

NODELET_INFO("Connecting to Bebop ...");
try
{
bebop_ptr_->Connect(nh, private_nh);
bebop_ptr_->Connect(nh, private_nh, param_bebop_ip);

if (param_reset_settings)
{
Expand Down

0 comments on commit 5bcdfb4

Please sign in to comment.