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

Added images to generate an animated intermitent effect.

parent ee8da1ae
No related branches found
No related tags found
No related merge requests found
......@@ -39,9 +39,11 @@ from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
# Name Type Reconf.level Description standard Min Max
gen.add("rate", double_t, SensorLevels.RECONFIGURE_STOP, "Main loop rate (Hz)", 10.0, 0.1, 1000.0)
gen.add("serial_port", str_t, SensorLevels.RECONFIGURE_STOP, "Serial port Linux device", "/dev/ttyACM0")
gen.add("baudrate", int_t, SensorLevels.RECONFIGURE_STOP, "Serial port baudrate", 56700, 9600, 1000000)
gen.add("device_id", int_t, SensorLevels.RECONFIGURE_STOP, "car_lights device ID", 1, 1, 254)
gen.add("rate", double_t, SensorLevels.RECONFIGURE_STOP, "Main loop rate (Hz)", 10.0, 0.1, 1000.0)
gen.add("serial_port", str_t, SensorLevels.RECONFIGURE_STOP, "Serial port Linux device", "/dev/ttyACM0")
gen.add("baudrate", int_t, SensorLevels.RECONFIGURE_STOP, "Serial port baudrate", 56700, 9600, 1000000)
gen.add("device_id", int_t, SensorLevels.RECONFIGURE_STOP, "car_lights device ID", 1, 1, 254)
gen.add("left_intermitent_file", str_t, SensorLevels.RECONFIGURE_STOP, "Image to use for the rear left intermitent lights", "")
gen.add("right_intermitent_file", str_t, SensorLevels.RECONFIGURE_STOP, "Image to use for the rear right intermitent lights", "")
exit(gen.generate(PACKAGE, "AdcCarLightsDriver", "AdcCarLights"))
File added
File added
......@@ -13,6 +13,8 @@
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
<rosparam file="$(arg config_file)" command="load"/>
<param name="left_intermitent_file" value="$(find iri_adc_car_lights)/config/intermitent_left.ppm"/>
<param name="right_intermitent_file" value="$(find iri_adc_car_lights)/config/intermitent_right.ppm"/>
<remap from="~/set_lights" to="$(arg set_lights_service)"/>
</node>
......
......@@ -3,7 +3,7 @@
<arg name="output" default="screen"/>
<arg name="launch_prefix" default=""/>
<arg name="dr" default="true"/>
<arg name="dr" default="false"/>
<include file="$(find iri_adc_car_lights)/launch/node.launch">
<arg name="node_name" value="iri_adc_car_lights"/>
......
......@@ -214,11 +214,11 @@ void AdcCarLightsDriver::set_standard(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=255;
color.G=255;
color.B=255;
color.R=32;
color.G=32;
color.B=32;
this->frame_buffer->set_color(color,this->whole_front_area);
color.R=128;
color.R=16;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->whole_rear_area);
......@@ -237,19 +237,19 @@ void AdcCarLightsDriver::set_brake(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=255;
color.G=255;
color.B=255;
color.R=32;
color.G=32;
color.B=32;
this->frame_buffer->set_color(color,this->whole_front_area);
color.R=255;
color.R=32;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_left_area);
color.R=255;
color.R=32;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_right_area);
color.R=128;
color.R=16;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_center_area);
......@@ -263,24 +263,27 @@ void AdcCarLightsDriver::set_brake(void)
void AdcCarLightsDriver::set_turn_left(void)
{
TPixelRGB max,min,color;
unsigned int index_mtn=-1;
try{
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=255;
color.G=255;
color.B=255;
color.R=32;
color.G=32;
color.B=32;
this->frame_buffer->set_color(color,this->front_right_area);
max.R=255;
max.G=64;
max.R=32;
max.G=8;
max.B=0;
min.R=0;
min.G=0;
min.B=0;
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->front_left_area);
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->rear_left_area);
color.R=128;
index_mtn=this->frame_buffer->add_ramp_motion(0.02,7,0,-12,0,0,false);
this->frame_buffer->load_image(0,this->config_.left_intermitent_file);
this->frame_buffer->add_image_display(0,0,0,0,index_mtn,-1,this->rear_left_area);
color.R=16;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_center_area);
......@@ -295,24 +298,27 @@ void AdcCarLightsDriver::set_turn_left(void)
void AdcCarLightsDriver::set_turn_right(void)
{
TPixelRGB max,min,color;
unsigned int index_mtn=-1;
try{
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=255;
color.G=255;
color.B=255;
color.R=32;
color.G=32;
color.B=32;
this->frame_buffer->set_color(color,this->front_left_area);
max.R=255;
max.G=64;
max.R=32;
max.G=8;
max.B=0;
min.R=0;
min.G=0;
min.B=0;
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->front_right_area);
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->rear_right_area);
color.R=128;
index_mtn=this->frame_buffer->add_ramp_motion(0.02,12,0,-7,0,0,true);
this->frame_buffer->load_image(0,this->config_.right_intermitent_file);
this->frame_buffer->add_image_display(0,0,0,0,index_mtn,-1,this->rear_right_area);
color.R=16;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_center_area);
......@@ -334,7 +340,7 @@ void AdcCarLightsDriver::set_parked(void)
this->frame_buffer->clear_all_patterns();
color.R=0;
color.G=0;
color.B=255;
color.B=32;
this->frame_buffer->set_color(color,this->whole_area);
}
}catch(CException &e){
......@@ -351,8 +357,8 @@ void AdcCarLightsDriver::set_emergency(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
max.R=255;
max.G=64;
max.R=32;
max.G=8;
max.B=0;
min.R=0;
min.G=0;
......@@ -373,12 +379,12 @@ void AdcCarLightsDriver::set_health(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
max.R=255;
max.R=32;
max.G=0;
max.B=0;
min.R=0;
min.G=0;
min.B=255;
min.B=32;
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->whole_area);
}
}catch(CException &e){
......@@ -396,7 +402,7 @@ void AdcCarLightsDriver::set_charge(void)
{
this->frame_buffer->clear_all_patterns();
max.R=0;
max.G=255;
max.G=32;
max.B=0;
min.R=0;
min.G=0;
......
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