diff --git a/cfg/AdcCarLights.cfg b/cfg/AdcCarLights.cfg index f5a4fe9ea79a7300065f43feda98dcd6873164ba..366358636368b7cec1cc1d29e2d56b1fbce12fea 100755 --- a/cfg/AdcCarLights.cfg +++ b/cfg/AdcCarLights.cfg @@ -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")) diff --git a/config/intermitent_left.ppm b/config/intermitent_left.ppm new file mode 100644 index 0000000000000000000000000000000000000000..f28e8597e20d6dab042a0f84aa91feda85fabf52 Binary files /dev/null and b/config/intermitent_left.ppm differ diff --git a/config/intermitent_right.ppm b/config/intermitent_right.ppm new file mode 100644 index 0000000000000000000000000000000000000000..72735f9395c515c73982f2acf38fb359ec033e1d Binary files /dev/null and b/config/intermitent_right.ppm differ diff --git a/launch/node.launch b/launch/node.launch index 6f27a49f833db4784b912f29f9739fc687e79c06..51aed6f47a228ffb8a90bdebec3f1d560767da97 100644 --- a/launch/node.launch +++ b/launch/node.launch @@ -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> diff --git a/launch/test.launch b/launch/test.launch index 63f134511a0ea22ea6f2927b4c3fcdb9b17d0e76..b6fe6b2b09f86182d9bd406d2e35941bf9dfe29b 100644 --- a/launch/test.launch +++ b/launch/test.launch @@ -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"/> diff --git a/src/adc_car_lights_driver.cpp b/src/adc_car_lights_driver.cpp index a45e6c8fd2cc682ab5b6c87de6b97b7949b985ac..9e61b7588c793220ee0b7da14abafeeb16dd14b6 100644 --- a/src/adc_car_lights_driver.cpp +++ b/src/adc_car_lights_driver.cpp @@ -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;