From: Xavier L. <Ba...@us...> - 2012-05-15 14:47:24
|
This is an automated email from the git hooks/post-receive script. It was generated because a ref change was pushed to the repository containing the project "krobot". The branch, master has been updated via 387e765be280cde4559fa39b47ae6650e728b813 (commit) from 03e4d8dbf2a8a7216d261348799c2b9b6474ad74 (commit) Those revisions listed above that are new to this repository have not appeared on any other notification email; so we list those revisions in full, below. - Log ----------------------------------------------------------------- commit 387e765be280cde4559fa39b47ae6650e728b813 Author: Xavier Lagorce <Xav...@cr...> Date: Tue May 15 16:45:13 2012 +0200 [Controller_Motor_STM32] Bug fixes and detection ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmwares/lib/differential_drive.c b/elec/boards/Controller_Motor_STM32/Firmwares/lib/differential_drive.c index 01fa1d2..487ae75 100644 --- a/elec/boards/Controller_Motor_STM32/Firmwares/lib/differential_drive.c +++ b/elec/boards/Controller_Motor_STM32/Firmwares/lib/differential_drive.c @@ -148,8 +148,10 @@ static void NORETURN traj_following_process(void) { u2=w2*powf(cosf(rs.theta-params.ghost_state.theta),2)+v_rot; // Apply command - dd_set_linear_speed(u1, 0.); - dd_set_rotational_speed(u2, 0.); + if (params.working) { + dd_set_linear_speed(u1, 0.); + dd_set_rotational_speed(u2, 0.); + } // Keep current time last_time = cur_time; diff --git a/elec/boards/Controller_Motor_STM32/Firmwares/lib/motor_controller.c b/elec/boards/Controller_Motor_STM32/Firmwares/lib/motor_controller.c index 6caa48f..2c2ae81 100644 --- a/elec/boards/Controller_Motor_STM32/Firmwares/lib/motor_controller.c +++ b/elec/boards/Controller_Motor_STM32/Firmwares/lib/motor_controller.c @@ -209,7 +209,12 @@ static void NORETURN motorController_process(void) { params->last_encoder_pos = encoder_pos; // Apply command - motorSetSpeed(params->motor, (int32_t)params->last_command); + if (isnan(params->last_command)) { + motorSetSpeed(params->motor, 0); + motor_led_on(params->motor); + } else { + motorSetSpeed(params->motor, (int32_t)params->last_command); + } } timer_waitEvent(&timer); // Wait for the remaining of the sample period } hooks/post-receive -- krobot |