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

Modified the LED's areas to match the real car.

Using the maximum intensity of the LED's.
parent 8bfb3bcc
No related branches found
No related tags found
No related merge requests found
......@@ -26,48 +26,48 @@ bool AdcCarLightsDriver::openDriver(void)
// whole front area
this->whole_front_area.min_row=0;
this->whole_front_area.max_row=0;
this->whole_front_area.min_col=0;
this->whole_front_area.max_col=7;
this->whole_front_area.min_col=16;
this->whole_front_area.max_col=23;
// front right area
this->front_right_area.min_row=0;
this->front_right_area.max_row=0;
this->front_right_area.min_col=0;
this->front_right_area.max_col=3;
this->front_right_area.min_col=16;
this->front_right_area.max_col=19;
// front left area
this->front_left_area.min_row=0;
this->front_left_area.max_row=0;
this->front_left_area.min_col=4;
this->front_left_area.max_col=7;
this->front_left_area.min_col=20;
this->front_left_area.max_col=23;
// rear left area
this->rear_left_area.min_row=0;
this->rear_left_area.max_row=0;
this->rear_left_area.min_col=8;
this->rear_left_area.max_col=11;
this->rear_left_area.min_col=0;
this->rear_left_area.max_col=3;
// rear center area
this->rear_center_area.min_row=0;
this->rear_center_area.max_row=0;
this->rear_center_area.min_col=12;
this->rear_center_area.max_col=19;
this->rear_center_area.min_col=4;
this->rear_center_area.max_col=11;
// rear middle left area
this->rear_middle_left_area.min_row=0;
this->rear_middle_left_area.max_row=0;
this->rear_middle_left_area.min_col=12;
this->rear_middle_left_area.max_col=15;
this->rear_middle_left_area.min_col=4;
this->rear_middle_left_area.max_col=7;
// rear middle right area
this->rear_middle_right_area.min_row=0;
this->rear_middle_right_area.max_row=0;
this->rear_middle_right_area.min_col=16;
this->rear_middle_right_area.max_col=19;
this->rear_middle_right_area.min_col=8;
this->rear_middle_right_area.max_col=11;
// rear right area
this->rear_right_area.min_row=0;
this->rear_right_area.max_row=0;
this->rear_right_area.min_col=20;
this->rear_right_area.max_col=23;
this->rear_right_area.min_col=12;
this->rear_right_area.max_col=15;
// whole rear area
this->whole_rear_area.min_row=0;
this->whole_rear_area.max_row=0;
this->whole_rear_area.min_col=8;
this->whole_rear_area.max_col=23;
this->whole_rear_area.min_col=0;
this->whole_rear_area.max_col=15;
return true;
}catch(CException &e){
ROS_WARN_STREAM(e.what());
......@@ -167,11 +167,11 @@ void AdcCarLightsDriver::set_standard(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=32;
color.G=32;
color.B=32;
color.R=255;
color.G=255;
color.B=255;
this->frame_buffer->set_color(color,this->whole_front_area);
color.R=16;
color.R=128;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->whole_rear_area);
......@@ -190,19 +190,19 @@ void AdcCarLightsDriver::set_brake(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=32;
color.G=32;
color.B=32;
color.R=255;
color.G=255;
color.B=255;
this->frame_buffer->set_color(color,this->whole_front_area);
color.R=32;
color.R=255;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_left_area);
color.R=32;
color.R=255;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_right_area);
color.R=16;
color.R=128;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_center_area);
......@@ -222,12 +222,12 @@ void AdcCarLightsDriver::set_turn_left(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=32;
color.G=32;
color.B=32;
color.R=255;
color.G=255;
color.B=255;
this->frame_buffer->set_color(color,this->front_right_area);
max.R=32;
max.G=8;
max.R=255;
max.G=64;
max.B=0;
min.R=0;
min.G=0;
......@@ -236,7 +236,7 @@ void AdcCarLightsDriver::set_turn_left(void)
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);
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->front_left_area);
color.R=16;
color.R=128;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_center_area);
......@@ -257,12 +257,12 @@ void AdcCarLightsDriver::set_turn_right(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
color.R=32;
color.G=32;
color.B=32;
color.R=255;
color.G=255;
color.B=255;
this->frame_buffer->set_color(color,this->front_left_area);
max.R=32;
max.G=8;
max.R=255;
max.G=64;
max.B=0;
min.R=0;
min.G=0;
......@@ -271,7 +271,7 @@ void AdcCarLightsDriver::set_turn_right(void)
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);
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->front_right_area);
color.R=16;
color.R=128;
color.G=0;
color.B=0;
this->frame_buffer->set_color(color,this->rear_center_area);
......@@ -293,7 +293,7 @@ void AdcCarLightsDriver::set_parked(void)
this->frame_buffer->clear_all_patterns();
color.R=0;
color.G=0;
color.B=32;
color.B=255;
this->frame_buffer->set_color(color,this->whole_area);
}
}catch(CException &e){
......@@ -310,8 +310,8 @@ void AdcCarLightsDriver::set_emergency(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
max.R=32;
max.G=8;
max.R=255;
max.G=64;
max.B=0;
min.R=0;
min.G=0;
......@@ -332,12 +332,12 @@ void AdcCarLightsDriver::set_health(void)
if(this->frame_buffer!=NULL)
{
this->frame_buffer->clear_all_patterns();
max.R=32;
max.R=255;
max.G=0;
max.B=0;
min.R=0;
min.G=0;
min.B=32;
min.B=255;
this->frame_buffer->add_square_waveform(1.0,0.5,max,min,this->whole_area);
}
}catch(CException &e){
......@@ -355,7 +355,7 @@ void AdcCarLightsDriver::set_charge(void)
{
this->frame_buffer->clear_all_patterns();
max.R=0;
max.G=32;
max.G=255;
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