Skip to content
Snippets Groups Projects
Commit 7800f12a authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Update node/nodelet.launch files, and some parameters and nodehandles

parent 07e48c6c
No related branches found
No related tags found
1 merge request!1Kinetic migration
......@@ -3,13 +3,9 @@ camera_name: firewire_camera
frame_id: camera_frame
Camera_node: 0 #-1=use serial, 0,1,2...=use camera
Camera_serial: ""
#known serials
#FLEA2-R: 00b09d0100a96262
#FLEA2-L: 00b09d01006cf72a
#bumblebee dabo: 0814438300001f9c
#bumblebee tibi: ????????????????
ISO_speed: 400
Image_width: 1024
Image_height: 768
......
......@@ -2,23 +2,32 @@
<!-- -->
<launch>
<arg name="name" default="robot" />
<arg name="ns" default="robot" />
<arg name="name" default="firewire"/>
<arg name="config_file" default="$(find iri_firewire_camera_driver)/config/default_camera.yaml" />
<arg name="cal_file" default="file://$(find iri_firewire_camera_driver)/calibration/default_camera.yaml"/>
<arg name="output" default="screen" />
<arg name="launch_prefix" default="" />
<arg name="cal_file" default="file://$(find iri_firewire_camera_driver)/calibration/default_camera.yaml"/>
<group ns="$(arg name)">
<group ns="$(arg ns)">
<node pkg ="iri_firewire_camera_driver"
type="iri_firewire_camera_driver"
name="firewire_camera"
name="$(arg name)"
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
<rosparam file="$(arg config_file)" command="load" />
<param name="cal_file" value="$(arg cal_file)"/>
<param name="cal_file" value="$(arg cal_file)"/>
</node>
</group>
</launch>
\ No newline at end of file
</launch>
<!--
published
/<arg ns>/<arg name>/*
/robot/firewire/image_raw
/robot/firewire/camera_info
-->
\ No newline at end of file
......@@ -3,7 +3,7 @@
<launch>
<arg name="name" default="robot" />
<arg name="config_file" default="$(find iri_firewire_camera_driver)/config/params.yaml" />
<arg name="config_file" default="$(find iri_firewire_camera_driver)/config/default_camera.yaml" />
<arg name="output" default="log" />
<arg name="launch_prefix" default="" />
......@@ -14,7 +14,7 @@
name="standalone_nodelet"
args="manager"
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
launch-prefix="$(arg launch_prefix)"/>
<node pkg="nodelet"
type="nodelet"
......@@ -31,4 +31,4 @@
<!-- TODO remaps image_raw, camera_info-->
<!-- TODO params nodelet? -->
<!-- TODO test with image_proc/crop_decimate, image_proc/rectify
\ No newline at end of file
<!-- TODO test with image_proc/crop_decimate, image_proc/rectify -->
\ No newline at end of file
......@@ -120,7 +120,7 @@ bool FirewireCameraDriver::startDriver(void)
return true;
}catch(CException &e){
this->unlock();
//ROS_INFO(e.what().data());
ROS_ERROR("FirewireCameraDriver:startDriver:Exception: %s", e.what().data());
return false;
}
}
......@@ -140,7 +140,7 @@ bool FirewireCameraDriver::stopDriver(void)
return true;
}catch(CException &e){
this->unlock();
//ROS_INFO(e.what().data());
ROS_ERROR("FirewireCameraDriver:stopDriver:Exception: %s", e.what().data());
return false;
}
}
......@@ -340,7 +340,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
this->camera->enable_feature(DC1394_FEATURE_WHITE_BALANCE);
}catch(CFirewireFeatureException &e){
(*enable)=false;
ROS_ERROR("FirewireCameraDriver: The white balance feature can not be enabled");
ROS_WARN("FirewireCameraDriver: The white balance feature can not be enabled");
return;
}
if((*mode)==0)
......@@ -359,7 +359,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
this->camera->set_feature_manual(DC1394_FEATURE_WHITE_BALANCE);
}catch(CFirewireFeatureException &e){
(*mode)=0;
ROS_ERROR("FirewireCameraDriver: The white balance feature can not be set in manual mode");
ROS_WARN("FirewireCameraDriver: The white balance feature can not be set in manual mode");
return;
}
try{
......@@ -378,7 +378,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
this->camera->disable_feature(DC1394_FEATURE_WHITE_BALANCE);
}catch(CFirewireFeatureException &e){
(*enable)=true;
ROS_ERROR("FirewireCameraDriver: The white balance feature can not be disabled");
ROS_WARN("FirewireCameraDriver: The white balance feature can not be disabled");
return;
}
}
......@@ -386,7 +386,7 @@ void FirewireCameraDriver::set_white_balance(bool *enable,int *mode, int *u_b_va
else
{
(*enable)=false;
ROS_ERROR("FirewireCameraDriver: The white balance feature is not present");
ROS_WARN("FirewireCameraDriver: The white balance feature is not present");
}
}catch(CFirewireInternalException &e){
ROS_ERROR("FirewireCameraDriver: Impossible to set the white balance feature");
......@@ -405,7 +405,7 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
this->camera->enable_feature(DC1394_FEATURE_SHUTTER);
}catch(CFirewireFeatureException &e){
(*enable)=false;
ROS_ERROR("FirewireCameraDriver: The shutter feature is not present");
ROS_WARN("FirewireCameraDriver: The shutter feature is not present");
return;
}
if((*mode)==0)
......@@ -443,7 +443,7 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
this->camera->disable_feature(DC1394_FEATURE_SHUTTER);
}catch(CFirewireFeatureException &e){
(*enable)=true;
ROS_ERROR("FirewireCameraDriver: The shutter feature can not be disabled");
ROS_WARN("FirewireCameraDriver: The shutter feature can not be disabled");
return;
}
}
......@@ -451,7 +451,7 @@ void FirewireCameraDriver::set_shutter(bool *enable,int *mode, int *value)
else
{
(*enable)=false;
ROS_ERROR("FirewireCameraDriver: The shutter feature is not present");
ROS_WARN("FirewireCameraDriver: The shutter feature is not present");
}
}catch(CFirewireInternalException &e){
ROS_ERROR("FirewireCameraDriver: Impossible to set the shutter feature");
......@@ -470,7 +470,7 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
this->camera->enable_feature(DC1394_FEATURE_GAIN);
}catch(CFirewireFeatureException &e){
(*enable)=false;
ROS_ERROR("FirewireCameraDriver: The gain feature is not present");
ROS_WARN("FirewireCameraDriver: The gain feature is not present");
return;
}
if((*mode)==0)
......@@ -508,7 +508,7 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
this->camera->disable_feature(DC1394_FEATURE_GAIN);
}catch(CFirewireFeatureException &e){
(*enable)=true;
ROS_ERROR("FirewireCameraDriver: The gain feature can not be disabled");
ROS_WARN("FirewireCameraDriver: The gain feature can not be disabled");
return;
}
}
......@@ -516,7 +516,7 @@ void FirewireCameraDriver::set_gain(bool *enable, int *mode, int *value)
else
{
(*enable)=false;
ROS_ERROR("FirewireCameraDriver: The gain feature is not present");
ROS_WARN("FirewireCameraDriver: The gain feature is not present");
}
}catch(CFirewireInternalException &e){
ROS_ERROR("FirewireCameraDriver: Impossible to set the gain feature");
......
#include "firewire_camera_driver_node.h"
FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_base_driver::IriBaseNodeDriver<FirewireCameraDriver>(nh),
camera_manager(ros::NodeHandle(this->public_node_handle_))
camera_manager(ros::NodeHandle(nh))
{
std::string cal_file;
bool cal_ok=false;
......@@ -13,20 +13,21 @@ FirewireCameraDriverNode::FirewireCameraDriverNode(ros::NodeHandle &nh) : iri_ba
this->desired_framerate=30.0;
this->diagnosed_camera_image=NULL;
this->camera.it.reset(new image_transport::ImageTransport(this->public_node_handle_));
this->camera.it.reset(new image_transport::ImageTransport(this->private_node_handle_));
this->camera.Image_msg_=sensor_msgs::ImagePtr(new sensor_msgs::Image);
this->diagnosed_camera_image = new diagnostic_updater::HeaderlessTopicDiagnostic("image_raw",this->diagnostic_,
diagnostic_updater::FrequencyStatusParam(&this->desired_framerate,&this->desired_framerate,0.01,5));
this->event_server=CEventServer::instance();
private_node_handle_.param<std::string>("camera_name", this->camera_name, "firewire_camera");
// [init publishers]
this->camera.camera_image_publisher_ = this->camera.it->advertiseCamera(this->camera_name+"/image_raw", 1);
this->camera.camera_image_publisher_ = this->camera.it->advertiseCamera("image_raw", 1);
// try to load the calibration file
private_node_handle_.param<std::string>("cal_file", cal_file, "");
private_node_handle_.param<std::string>("camera_name", this->camera_name, "firewire_camera");
this->camera_manager.setCameraName(this->camera_name);
if(this->camera_manager.validateURL(cal_file))
{
......@@ -132,7 +133,7 @@ void FirewireCameraDriverNode::mainNodeThread(void)
this->driver_.unlock();
}catch(CException &e){
this->driver_.unlock();
ROS_ERROR("FirewireCameraDriverNode: Impossible to capture frame");
ROS_ERROR("FirewireCameraDriverNode:Impossible to capture frame[%s]", e.what().c_str());
}
//fill srv structure and make request to the server
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment