Skip to content
Snippets Groups Projects
Commit 3272e1ee authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Changed the node to publish raw images.

Added a launch file to launch all the necessary nodes for the ar_pose detection.
parent 0251c02f
No related branches found
No related tags found
No related merge requests found
......@@ -4,12 +4,12 @@
name="iri_firewire_camera"
type="iri_firewire_camera"
output="screen">
<param name="Camera_node" value="0" />
<param name="Camera_node" value="2" />
<param name="Color_coding" value="0" />
<param name="ISO_speed" value="400" />
<param name="Framerate" value="30" />
<param name="Image_width" value="640" />
<param name="Image_height" value="480" />
<param name="Image_width" value="1024" />
<param name="Image_height" value="768" />
</node>
<!-- <node pkg="image_view"
......
<launch>
<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen">
<param name="Camera_node" value="2" />
<param name="frame_id" value="bumblebee_frame" type="string" />
<param name="cal_file" value="file://$(find iri_firewire_camera)/calibration/$(env ROBOT)_right_camera.yaml" type="string" />
<param name="ISO_speed" value="400" />
<param name="Framerate" value="7.5" />
<param name="Color_coding" value="6" />
<param name="Image_width" value="1024" />
<param name="Image_height" value="768" />
<param name="autosize" value="true"/>
<remap from="/standalone_nodelet/camera_image"
to="/camera/image_raw" />
<remap from="/standalone_nodelet/camera_info"
to="/camera/camera_info" />
</node>
<!-- firewire camera driver -->
<node pkg="nodelet" type="nodelet" name="iri_firewire_nodelet" args="load iri_firewire_camera/FirewireCameraNodelet standalone_nodelet" output="screen">
</node>
<node pkg ="nodelet" type="nodelet" name="image_proc_debayer" args="load image_proc/debayer standalone_nodelet" output="screen">
<remap from="/image_raw"
to="/camera/image_raw"/>
<remap from="/camera_info"
to="/camera/camera_info"/>
<remap from="/image_mono"
to="/camera/image_mono"/>
</node>
<!-- image rectification -->
<node pkg ="nodelet" type="nodelet" name="image_proc_rect" args="load image_proc/rectify standalone_nodelet" output="screen">
<remap from="/image_mono"
to="/camera/image_mono"/>
<remap from="/camera_info"
to="/camera/camera_info"/>
<remap from="/image_rect"
to="/camera/image_rect"/>
</node>
<node pkg ="nodelet" type="nodelet" name="local_th" args="load iri_image_local_binarization/ImageLocalBinNodelet standalone_nodelet" output="screen">
<remap from="local_th/image_in/image_raw"
to="/camera/image_rect"/>
<remap from="local_th/image_in/camera_info"
to="/camera/camera_info"/>
<remap from="local_th/image_out/image_raw"
to="/ar_pose/image_raw"/>
<remap from="local_th/image_out/camera_info"
to="/ar_pose/camera_info"/>
</node>
<node name="ar_pose"
pkg ="ar_pose"
type="ar_multi"
respawn="false"
output="screen">
<param name="marker_pattern_list" type="string" value="$(find iri_ladybug2)/data/object_4x4_front"/>
<param name="threshold" type="int" value="100"/>
<param name="use_history" type="bool" value="true"/>
<remap from="/camera/image_raw"
to="/ar_pose/image_raw"/>
<remap from="/camera/camera_info"
to="/ar_pose/camera_info"/>
</node>
</launch>
<launch>
<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen">
<param name="Camera_node" value="0" />
<param name="Camera_node" value="1" />
<param name="frame_id" value="bumblebee_frame" type="string" />
<param name="cal_file" value="file://$(find iri_firewire_camera)/calibration/$(env ROBOT)_right_camera.yaml" type="string" />
<param name="ISO_speed" value="400" />
......
......@@ -72,7 +72,7 @@ void FirewireCameraDriverNode::mainNodeThread(void)
this->Image_msg_->height=config.height;
this->Image_msg_->step=config.width*config.depth/8;
this->Image_msg_->data=std::vector<unsigned char>(image_data,image_data+config.width*config.height*config.depth/8);
if(config.coding==MONO || config.coding==RAW)
if(config.coding==MONO)
{
if(config.depth==DEPTH8)
this->Image_msg_->encoding="8UC1";
......@@ -81,6 +81,10 @@ void FirewireCameraDriverNode::mainNodeThread(void)
else
this->Image_msg_->encoding="16UC1";
}
else if(config.coding==RAW)
{
this->Image_msg_->encoding="bayer_rggb8";
}
else if(config.coding==YUV)
{
this->Image_msg_->encoding="yuv422";
......
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