You can subscribe to this list here.
2009 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
(13) |
---|---|---|---|---|---|---|---|---|---|---|---|---|
2010 |
Jan
(50) |
Feb
(137) |
Mar
(84) |
Apr
(36) |
May
(100) |
Jun
(5) |
Jul
|
Aug
(4) |
Sep
(13) |
Oct
(1) |
Nov
(4) |
Dec
(22) |
2011 |
Jan
(4) |
Feb
(9) |
Mar
(113) |
Apr
(76) |
May
(31) |
Jun
(19) |
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
|
2012 |
Jan
(4) |
Feb
|
Mar
(2) |
Apr
(6) |
May
(19) |
Jun
|
Jul
|
Aug
|
Sep
|
Oct
(4) |
Nov
|
Dec
|
2013 |
Jan
|
Feb
|
Mar
(2) |
Apr
(22) |
May
(6) |
Jun
|
Jul
|
Aug
|
Sep
|
Oct
(1) |
Nov
|
Dec
|
2014 |
Jan
|
Feb
|
Mar
|
Apr
|
May
(1) |
Jun
|
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
|
From: Xavier L. <Ba...@us...> - 2011-04-21 12:29:13
|
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 362646a87e0f22370a259e4d0ce0bf13c2f707bb (commit) from 9641f603275a43c3f07862973aea212c2e0ced9c (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 362646a87e0f22370a259e4d0ce0bf13c2f707bb Author: Xavier Lagorce <Xav...@cr...> Date: Thu Apr 21 14:28:44 2011 +0200 [Controller_Motor_STM32] With correct header inclusion ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c index d467b7d..83fe983 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c @@ -10,7 +10,7 @@ #include "bezier_utils.h" #ifdef BEZIER_UTILS_USE_BERTOS -#include <kern/proc.h> +#include <cpu/power.h> #endif float bezier_apply(float params[4], float u) { hooks/post-receive -- krobot |
From: Xavier L. <Ba...@us...> - 2011-04-21 12:25:08
|
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 9641f603275a43c3f07862973aea212c2e0ced9c (commit) via 7797e8dd88a52c7e6767729bd606e9aa632920af (commit) from 731b470ef6cd5b6d93a2b2e2a85182f1c535b4b8 (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 9641f603275a43c3f07862973aea212c2e0ced9c Author: Xavier Lagorce <Xav...@cr...> Date: Thu Apr 21 14:24:31 2011 +0200 [Controller_Motor_STM32] Release CPU during speed profile computation for Bezier Splines commit 7797e8dd88a52c7e6767729bd606e9aa632920af Author: Xavier Lagorce <Xav...@cr...> Date: Thu Apr 21 14:00:47 2011 +0200 [Controller_Motor_STM32] Fix convertion problem between seconds and systicks in odometry. ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c index 0b74fde..d467b7d 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c @@ -9,6 +9,10 @@ #include "bezier_utils.h" +#ifdef BEZIER_UTILS_USE_BERTOS +#include <kern/proc.h> +#endif + float bezier_apply(float params[4], float u) { return (params[0] + params[1]*u + params[2]*u*u + params[3]*u*u*u); } @@ -62,6 +66,10 @@ void bezier_velocity_profile(float dparams[2][4], float ddparams[2][4], vmins[ind] = v_end; ind++; +#ifdef BEZIER_UTILS_USE_BERTOS + cpu_relax(); +#endif + // Compute speed limitations for (j=0; j < ind; j++) { im = mins[j]; @@ -95,6 +103,10 @@ void bezier_velocity_profile(float dparams[2][4], float ddparams[2][4], break; } } + +#ifdef BEZIER_UTILS_USE_BERTOS + cpu_relax(); +#endif } // end if (vm < v_max) } // for mins } diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h index c36fd62..2aa45fd 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h @@ -10,6 +10,8 @@ #ifndef __BEZIER_UTILS_H #define __BEZIER_UTILS_H +#define BEZIER_UTILS_USE_BERTOS + #include <math.h> #include <stdint.h> diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/odometry.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/odometry.c index 208c342..ab0f7eb 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/odometry.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/odometry.c @@ -59,7 +59,7 @@ static void NORETURN odometry_process(void) { Timer timer; // configure timer - timer_setDelay(&timer, ms_to_ticks(state.Ts)); + timer_setDelay(&timer, ms_to_ticks(1000 * state.Ts)); timer_setEvent(&timer); // Indicate we are running hooks/post-receive -- krobot |
From: Xavier L. <Ba...@us...> - 2011-04-21 11:57:04
|
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 731b470ef6cd5b6d93a2b2e2a85182f1c535b4b8 (commit) from 9c40637e10a40854186ed9a50c002088be65a64d (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 731b470ef6cd5b6d93a2b2e2a85182f1c535b4b8 Author: Xavier Lagorce <Xav...@cr...> Date: Thu Apr 21 13:56:21 2011 +0200 [Controller_Motor_STM32] Show differential drive status on LED1 with indicator thread. ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c index a132452..578cbdd 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c @@ -343,10 +343,13 @@ uint8_t dd_add_bezier(float x_end, float y_end, float d1, float d2, float end_an } uint8_t dd_get_ghost_state(robot_state_t *state, float *u) { - state->x = params.ghost_state.x; - state->y = params.ghost_state.y; - state->theta = params.ghost_state.theta; - *u = params.u; + if (state != NULL) { + state->x = params.ghost_state.x; + state->y = params.ghost_state.y; + state->theta = params.ghost_state.theta; + } + if (u != NULL) + *u = params.u; if (params.working == 1) return DD_GHOST_MOVING; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h index 96a8241..73d6944 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h @@ -100,6 +100,8 @@ uint8_t dd_add_bezier(float x_end, float y_end, float d1, float d2, float end_an * - state : pointer to a robot_state_t structure where the ghost state will be written * - u : pointer to a float in which to write the current value of the parameter on the spline * + * If one of these pointers is NULL, the associated value won't be written. + * * return value : * - DD_GHOST_MOVING : if a trajectory is currently followed * - DD_GHOST_STOPPED : if the ghost robot is stopped diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c index 9efbc67..4b10660 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c @@ -94,7 +94,7 @@ static void init(void) static void NORETURN ind_process(void) { while(1) { - if (tc_is_working(MOTOR3 | MOTOR4)) { + if (dd_get_ghost_state(NULL, NULL) == DD_GHOST_MOVING) { LED1_ON(); } else { LED1_OFF(); hooks/post-receive -- krobot |
From: Xavier L. <Ba...@us...> - 2011-04-21 11:46:55
|
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 9c40637e10a40854186ed9a50c002088be65a64d (commit) from 3bf7caba254cd6a7beabb131102adc5a5d71fa43 (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 9c40637e10a40854186ed9a50c002088be65a64d Author: Xavier Lagorce <Xav...@cr...> Date: Thu Apr 21 13:46:21 2011 +0200 [Controller_Motor_STM32] Cleanup ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c index 2a4b2c5..a132452 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c @@ -66,7 +66,6 @@ static void NORETURN traj_following_process(void) { proc_exit(); } else { if (!params.working && params.trajs[next_traj].initialized) { - LED2_ON(); params.working = 1; params.u = 0; ui = 0; @@ -85,8 +84,6 @@ static void NORETURN traj_following_process(void) { // Stop following the trajectory if we are close enough to our goal if (params.u >= 1.0 || ((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { - //if (((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { - LED2_OFF(); params.working = 0; traj->initialized = 0; traj->enabled = 0; @@ -126,18 +123,14 @@ static void NORETURN traj_following_process(void) { dxu = bezier_apply(traj->dparams[0], params.u); dyu = bezier_apply(traj->dparams[1], params.u); params.u += v_lin/sqrtf(dxu*dxu+dyu*dyu)*dt; - //if (u >= 1.0) { - // u = 1.0; - //} else { - params.ghost_state.x += v_lin*cosf(params.ghost_state.theta)*dt; - params.ghost_state.y += v_lin*sinf(params.ghost_state.theta)*dt; - params.ghost_state.theta = fmodf(params.ghost_state.theta + v_rot*dt, 2*M_PI); - if (params.ghost_state.theta > M_PI) { - params.ghost_state.theta -= 2*M_PI; - } else if (params.ghost_state.theta <= M_PI) { - params.ghost_state.theta += 2*M_PI; - } - //} + params.ghost_state.x += v_lin*cosf(params.ghost_state.theta)*dt; + params.ghost_state.y += v_lin*sinf(params.ghost_state.theta)*dt; + params.ghost_state.theta = fmodf(params.ghost_state.theta + v_rot*dt, 2*M_PI); + if (params.ghost_state.theta > M_PI) { + params.ghost_state.theta -= 2*M_PI; + } else if (params.ghost_state.theta <= M_PI) { + params.ghost_state.theta += 2*M_PI; + } // Compute command z1=(rs.x-params.ghost_state.x)*cosf(params.ghost_state.theta)+(rs.y-params.ghost_state.y)*sinf(params.ghost_state.theta); hooks/post-receive -- krobot |
From: Xavier L. <Ba...@us...> - 2011-04-20 21:33:37
|
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 3bf7caba254cd6a7beabb131102adc5a5d71fa43 (commit) from 736df6ea119063d15715e99a1d812b5411244871 (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 3bf7caba254cd6a7beabb131102adc5a5d71fa43 Author: Xavier Lagorce <Xav...@cr...> Date: Wed Apr 20 23:32:43 2011 +0200 [Controller_Motor_STM32] Changed some controller gains + more readibility ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c index 6b607e9..9efbc67 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c @@ -47,7 +47,13 @@ static void init(void) // Start control of drive motors tc_init(); - dd_start(WHEEL_RADIUS, SHAFT_WIDTH, 8*2*M_PI, 0.5, 1.0, 1.0, 0.7, 0.7, 1.0, 0.01); + dd_start(WHEEL_RADIUS, SHAFT_WIDTH, // Structural parameters + 8*2*M_PI, // Absolute wheel speed limitation + 0.5, // Linear velocity limitation + 1.0, // Linear acceleration limitation + 1.0, // Radial acceleration limitation + 0.4, 0.7, 1.0, // Controller gains + 0.005); // Sample period // Common parameters params.encoder_gain = -2.0*M_PI/2000.0/15.0; params.G0 = 0.0145; hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-20 21:13:52
|
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 736df6ea119063d15715e99a1d812b5411244871 (commit) from 1626abcabb9345aa8858641cc53da6a41b6d7033 (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 736df6ea119063d15715e99a1d812b5411244871 Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 23:13:15 2011 +0200 [krobot_planner] fix the sending of the trajectory when receiving a Send ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_planner.ml b/info/control2011/src/tools/krobot_planner.ml index 9c4b837..176826e 100644 --- a/info/control2011/src/tools/krobot_planner.ml +++ b/info/control2011/src/tools/krobot_planner.ml @@ -309,8 +309,9 @@ let handle_message planner (timestamp, message) = | Send -> ignore ( let ts = Unix.gettimeofday () in + let vertices = if planner.moving then planner.vertices else planner.position :: planner.vertices in join [ - Krobot_bus.send planner.bus (ts, Trajectory_vertices(planner.vertices, planner.curves)); + Krobot_bus.send planner.bus (ts, Trajectory_vertices(vertices, planner.curves)); Krobot_bus.send planner.bus (ts, Trajectory_moving planner.moving); ] ) hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-20 21:10:14
|
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 1626abcabb9345aa8858641cc53da6a41b6d7033 (commit) via a93c9138dcd65b01bb4b3432486557db62bb6847 (commit) via 0dc2179cc162ec5aefa4140793d9246f0d50ea6e (commit) from a23abb45064d154e262a1e82a3112976f082950e (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 1626abcabb9345aa8858641cc53da6a41b6d7033 Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 23:08:43 2011 +0200 [krobot_planner] clear the trajectory at the end of one commit a93c9138dcd65b01bb4b3432486557db62bb6847 Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 23:01:50 2011 +0200 [krobot_planner] do not remove the origin of the trajectory too early commit 0dc2179cc162ec5aefa4140793d9246f0d50ea6e Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 22:56:49 2011 +0200 [info] keep bezier curves in sync between the planner and the viewer ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/lib/krobot_bus.ml b/info/control2011/src/lib/krobot_bus.ml index 8633395..cf22f9d 100644 --- a/info/control2011/src/lib/krobot_bus.ml +++ b/info/control2011/src/lib/krobot_bus.ml @@ -25,8 +25,7 @@ type message = | Log of string | Send | Kill of string - | Trajectory_origin of vertice * vector - | Trajectory_vertices of vertice list + | Trajectory_vertices of vertice list * (vertice * vertice * vertice * vertice) list | Trajectory_set_vertices of vertice list | Trajectory_add_vertice of vertice | Trajectory_simplify of float @@ -67,15 +66,19 @@ let string_of_message = function sprintf "Kill %S" name - | Trajectory_origin(o, v) -> + | Trajectory_vertices(vertices, curves) -> sprintf - "Trajectory_origin(%s, %s)" - (string_of_vertice o) - (string_of_vector v) - | Trajectory_vertices l -> - sprintf - "Trajectory_vertices [%s]" - (String.concat "; " (List.map string_of_vertice l)) + "Trajectory_vertices([%s], [%s])" + (String.concat "; " (List.map string_of_vertice vertices)) + (String.concat "; " (List.map + (fun (p, q, r, s) -> + Printf.sprintf + "(%s, %s, %s, %s)" + (string_of_vertice p) + (string_of_vertice q) + (string_of_vertice r) + (string_of_vertice s)) + curves)) | Trajectory_set_vertices l -> sprintf "Trajectory_set_vertices [%s]" diff --git a/info/control2011/src/lib/krobot_bus.mli b/info/control2011/src/lib/krobot_bus.mli index fb1333a..c453e26 100644 --- a/info/control2011/src/lib/krobot_bus.mli +++ b/info/control2011/src/lib/krobot_bus.mli @@ -34,11 +34,9 @@ type message = (** Trajectory messages. *) - | Trajectory_origin of vertice * vector - (** The origin of the trajectory with the initial direction - vector. *) - | Trajectory_vertices of vertice list - (** The list of vertices for the planned trajectory. *) + | Trajectory_vertices of vertice list * (vertice * vertice * vertice * vertice) list + (** The list of vertices for the planned trajectory, along with + the bezier curves. *) | Trajectory_set_vertices of vertice list (** Sets the trajectory. *) | Trajectory_add_vertice of vertice diff --git a/info/control2011/src/tools/krobot_planner.ml b/info/control2011/src/tools/krobot_planner.ml index dec418e..9c4b837 100644 --- a/info/control2011/src/tools/krobot_planner.ml +++ b/info/control2011/src/tools/krobot_planner.ml @@ -38,14 +38,12 @@ type planner = { bus : Krobot_bus.t; (* The message bus used to communicate with the robot. *) - mutable origin : (vertice * vector); - (* If the robot is moving, this is the origin of the current - trajectory with the initial direction vector, otherwise it is the - current position with the current direction vector. *) - mutable vertices : vertice list; (* The list of vertices for the trajectory. *) + mutable curves : (vertice * vertice * vertice * vertice) list; + (* The parameters of bezier curves. *) + mutable moving : bool; (* Is the robot moving ? *) @@ -73,13 +71,26 @@ type planner = { | Primitives | +-----------------------------------------------------------------+ *) -let set_vertices planner vertices = +let set_vertices planner ?curves vertices = planner.vertices <- vertices; - ignore (Krobot_bus.send planner.bus (Unix.gettimeofday (), Trajectory_vertices vertices)) - -let set_origin planner (o, v) = - planner.origin <- (o, v); - ignore (Krobot_bus.send planner.bus (Unix.gettimeofday (), Trajectory_origin(o, v))) + (* If the robot is not moving, add its current position to the + trajectory. *) + let vertices = + match planner.moving with + | true -> vertices + | false -> planner.position :: vertices + in + (* Compute bezier curves if not provided. *) + let curves = + match curves with + | Some l -> + l + | None -> + let v = { vx = cos planner.orientation; vy = sin planner.orientation } in + List.rev (Bezier.fold_vertices (fun p q r s acc -> (p, q, r, s) :: acc) v vertices []) + in + planner.curves <- curves; + ignore (Krobot_bus.send planner.bus (Unix.gettimeofday (), Trajectory_vertices(vertices, curves))) let set_moving planner moving = planner.moving <- moving; @@ -198,11 +209,6 @@ let go planner rotation_speed rotation_acceleration moving_speed moving_accelera set_moving planner true; planner.mover <- ( try_lwt - let o, v = planner.origin in - - (* Compute all cubic bezier curves. *) - let params = List.rev (Bezier.fold_vertices (fun p q r s acc -> (p, q, r, s) :: acc) v (o :: planner.vertices) []) in - (* Send a bezier curve to the robot. *) let send_curve (p, q, r, s) v_end = (* Compute parameters. *) @@ -217,55 +223,55 @@ let go planner rotation_speed rotation_acceleration moving_speed moving_accelera ); (* Send the curve. *) - Krobot_message.send planner.bus (Unix.gettimeofday (), Motor_bezier(s.x, s.y, d1, d2, theta_end, v_end)) + lwt () = Krobot_message.send planner.bus (Unix.gettimeofday (), Motor_bezier(s.x, s.y, d1, d2, theta_end, v_end)) in + + return (s, theta_end) in (* Remove the first vertice of the trajecotry. *) - let drop_vertice () = - (match planner.vertices with - | _ :: l -> - set_vertices planner l - | [] -> - ()); - set_origin planner (planner.position, - { vx = cos planner.orientation; - vy = sin planner.orientation }) + let drop_vertice (s, theta) = + set_vertices planner ~curves:(List.tl planner.curves) (List.tl planner.vertices) in - let rec loop = function + let rec loop x = function | [] -> lwt () = wait_done planner in - drop_vertice (); + set_vertices planner []; return () | [points] -> lwt () = wait_middle planner in - lwt () = send_curve points 0.01 in + lwt _ = send_curve points 0.01 in + lwt () = wait_start planner in + drop_vertice x; lwt () = wait_done planner in - drop_vertice (); + set_vertices planner []; return () | points :: rest -> lwt () = wait_middle planner in - lwt () = send_curve points 0.5 in + lwt y = send_curve points 0.5 in lwt () = wait_start planner in - drop_vertice (); - loop rest + drop_vertice x; + loop y rest in - match params with + (* Add the origin of the trajectory to keep displaying it. *) + planner.vertices <- planner.position :: planner.vertices; + match planner.curves with | [] -> + set_vertices planner []; return () | [points] -> - lwt () = send_curve points 0.01 in + lwt _ = send_curve points 0.01 in lwt () = wait_done planner in - drop_vertice (); + set_vertices planner []; return () | points :: rest -> - lwt () = send_curve points 0.5 in - loop rest + lwt x = send_curve points 0.5 in + loop x rest with exn -> Lwt_log.error_f ~section ~exn "failed to move" @@ -287,11 +293,7 @@ let handle_message planner (timestamp, message) = match decode frame with | Odometry(x, y, theta) -> planner.position <- { x; y }; - planner.orientation <- math_mod_float theta (2. *. pi); - if not planner.moving then - set_origin planner (planner.position, - { vx = cos planner.orientation; - vy = sin planner.orientation }) + planner.orientation <- math_mod_float theta (2. *. pi) | Odometry_ghost(x, y, theta, u, following) -> planner.curve_status <- u; @@ -308,23 +310,26 @@ let handle_message planner (timestamp, message) = ignore ( let ts = Unix.gettimeofday () in join [ - Krobot_bus.send planner.bus (ts, Trajectory_origin(fst planner.origin, snd planner.origin)); - Krobot_bus.send planner.bus (ts, Trajectory_vertices planner.vertices); + Krobot_bus.send planner.bus (ts, Trajectory_vertices(planner.vertices, planner.curves)); Krobot_bus.send planner.bus (ts, Trajectory_moving planner.moving); ] ) | Trajectory_set_vertices l -> - set_vertices planner l + if not planner.moving then + set_vertices planner l | Trajectory_add_vertice vertice -> - set_vertices planner (planner.vertices @ [vertice]) + if not planner.moving then + set_vertices planner (planner.vertices @ [vertice]) | Trajectory_simplify tolerance -> - simplify planner tolerance + if not planner.moving then + simplify planner tolerance | Trajectory_go(rotation_speed, rotation_acceleration, moving_speed, moving_acceleration) -> - ignore (go planner rotation_speed rotation_acceleration moving_speed moving_acceleration) + if not planner.moving then + ignore (go planner rotation_speed rotation_acceleration moving_speed moving_acceleration) | Trajectory_stop -> cancel planner.mover; @@ -371,8 +376,8 @@ lwt () = (* Create a new planner. *) let planner = { bus; - origin = { x = 0.; y = 0. }, { vx = 1.; vy = 0. }; vertices = []; + curves = []; moving = false; motors_moving = false; curve_status = 0; diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index 9e22445..7ddee83 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -50,12 +50,12 @@ type viewer = { mutable beacon : beacon; (* The state of the beacon. *) - mutable origin : vertice * vector; - (* The origin of the trajectory. *) - mutable vertices : vertice list; (* The current trajectory. *) + mutable curves : (vertice * vertice * vertice * vertice) list; + (* The current bezier curves of the trajectory. *) + mutable motor_status : bool * bool * bool *bool; (* Status of the four motor controller. *) } @@ -268,18 +268,21 @@ let draw viewer = Cairo.stroke ctx end; - let o, v = viewer.origin in - (* Draw points. *) Cairo.set_source_rgb ctx 255. 255. 0.; - Cairo.move_to ctx o.x o.y; - List.iter (fun { x; y } -> Cairo.line_to ctx x y) viewer.vertices; - Cairo.stroke ctx; + (match viewer.vertices with + | [] -> + () + | o :: l -> + Cairo.move_to ctx o.x o.y; + List.iter (fun { x; y } -> Cairo.line_to ctx x y) l; + Cairo.stroke ctx); (* Draw bezier curves. *) Cairo.set_source_rgb ctx 255. 0. 255.; - Bezier.fold_curves - (fun curve () -> + List.iter + (fun (p, q, r, s) -> + let curve = Bezier.of_vertices p q r s in let { x; y } = Bezier.vertice curve 0. in Cairo.move_to ctx x y; for i = 1 to 100 do @@ -287,7 +290,7 @@ let draw viewer = Cairo.line_to ctx x y done; Cairo.stroke ctx) - v (o :: viewer.vertices) (); + viewer.curves; let ctx = Cairo_lablgtk.create viewer.ui#scene#misc#window in Cairo.set_source_surface ctx surface 0. 0.; @@ -397,12 +400,9 @@ let handle_message viewer (timestamp, message) = | Kill "viewer" -> exit 0 - | Trajectory_origin(o, v) -> - viewer.origin <- (o, v); - queue_draw viewer - - | Trajectory_vertices l -> - viewer.vertices <- l; + | Trajectory_vertices(vertices, curves) -> + viewer.vertices <- vertices; + viewer.curves <- curves; queue_draw viewer | Trajectory_moving moving -> @@ -468,8 +468,8 @@ lwt () = state = init; ghost = init; beacon = { xbeacon = 1.; ybeacon = 1.; valid = false }; - origin = ({ x = 0.; y = 0. }, { vx = 0.; vy = 0. }); vertices = []; + curves = []; statusbar_context = ui#statusbar#new_context ""; motor_status = (false, false, false, false); } in hooks/post-receive -- krobot |
From: Xavier L. <Ba...@us...> - 2011-04-20 19:01:41
|
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 a23abb45064d154e262a1e82a3112976f082950e (commit) from 5f3e029aaab36e94eb061e83d3a810f3c6c3adce (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 a23abb45064d154e262a1e82a3112976f082950e Author: Xavier Lagorce <Xav...@cr...> Date: Wed Apr 20 21:00:18 2011 +0200 [Controller_Motor_STM32] Send current position on the spline when moving ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h index 9980947..e7d2cd6 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h @@ -68,6 +68,7 @@ typedef struct { int16_t x __attribute__((__packed__)); // X position in mm (fixed point representation...) int16_t y __attribute__((__packed__)); // Y position in mm int16_t theta __attribute__((__packed__)); // angle in 1/10000 radians + uint8_t u; // Parameter on the spline between 0 and 255 uint8_t state; // 1 if trajectory in progress, 0 else } ghost_msg_t; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c index 9a86272..5f60fcb 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c @@ -51,6 +51,7 @@ static void NORETURN canMonitor_process(void) { status_can_msg_t status_msg; can_tx_frame txm; robot_state_t odometry; + float u; Timer timer_can; // Initialize constant parameters of TX frame @@ -117,10 +118,11 @@ static void NORETURN canMonitor_process(void) { timer_add(&timer_can); // Sending ghost state - msg_ghost.data.state = dd_get_ghost_state(&odometry); + msg_ghost.data.state = dd_get_ghost_state(&odometry, &u); msg_ghost.data.x = (int16_t)(odometry.x * 1000.0); msg_ghost.data.y = (int16_t)(odometry.y * 1000.0); msg_ghost.data.theta = (int16_t)(odometry.theta * 1000.0); + msg_ghost.data.u = (uint8_t)(u * 255); txm.data32[0] = msg_ghost.data32[0]; txm.data32[1] = msg_ghost.data32[1]; txm.eid = CAN_MSG_GHOST; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c index c22d8c8..2a4b2c5 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c @@ -27,7 +27,7 @@ typedef struct { uint8_t initialized, enabled, running, working; float wheel_radius, shaft_width; float last_lin_acceleration, last_rot_acceleration; - float v_max, at_max, ar_max; + float u, v_max, at_max, ar_max; command_generator_t left_wheel_speed, right_wheel_speed; command_generator_t left_wheel, right_wheel; uint8_t current_traj; @@ -44,7 +44,7 @@ static void NORETURN traj_following_process(void) { Timer timer; uint8_t next_traj, ui; robot_state_t rs; - float cr, u, v_lin, v_ratio, v_max, v_rot, dxu, dyu; + float cr, v_lin, v_ratio, v_max, v_rot, dxu, dyu; float z1, z2, z3, w1, w2, u1, u2, dt; dd_bezier_traj_t *traj; int32_t last_time, cur_time; @@ -68,7 +68,7 @@ static void NORETURN traj_following_process(void) { if (!params.working && params.trajs[next_traj].initialized) { LED2_ON(); params.working = 1; - u = 0; + params.u = 0; ui = 0; params.current_traj = next_traj; traj = ¶ms.trajs[params.current_traj]; @@ -84,7 +84,7 @@ static void NORETURN traj_following_process(void) { odo_getState(&rs); // Stop following the trajectory if we are close enough to our goal - if (u >= 1.0 || ((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { + if (params.u >= 1.0 || ((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { //if (((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { LED2_OFF(); params.working = 0; @@ -98,13 +98,13 @@ static void NORETURN traj_following_process(void) { } else { // We are following a trajectory, let's do it // Compute ghost vehicule parameters - cr = bezier_cr(u, traj->dparams, traj->ddparams); - for (; ui*traj->du <= u; ui++); + cr = bezier_cr(params.u, traj->dparams, traj->ddparams); + for (; ui*traj->du <= params.u; ui++); if (ui*traj->du > 1.0) ui--; if (ui > 0) { v_lin = traj->v_tab[ui-1] + - (traj->v_tab[ui]-traj->v_tab[ui-1]) * (u - traj->du*(ui-1))/traj->du; + (traj->v_tab[ui]-traj->v_tab[ui-1]) * (params.u - traj->du*(ui-1))/traj->du; } else { v_lin = traj->v_tab[0]; } @@ -123,9 +123,9 @@ static void NORETURN traj_following_process(void) { // Evolution of the ghost vehicule state cur_time = ticks_to_us(timer_clock()); dt = (cur_time - last_time) * 1e-6; - dxu = bezier_apply(traj->dparams[0], u); - dyu = bezier_apply(traj->dparams[1], u); - u += v_lin/sqrtf(dxu*dxu+dyu*dyu)*dt; + dxu = bezier_apply(traj->dparams[0], params.u); + dyu = bezier_apply(traj->dparams[1], params.u); + params.u += v_lin/sqrtf(dxu*dxu+dyu*dyu)*dt; //if (u >= 1.0) { // u = 1.0; //} else { @@ -349,10 +349,11 @@ uint8_t dd_add_bezier(float x_end, float y_end, float d1, float d2, float end_an } } -uint8_t dd_get_ghost_state(robot_state_t *state) { +uint8_t dd_get_ghost_state(robot_state_t *state, float *u) { state->x = params.ghost_state.x; state->y = params.ghost_state.y; state->theta = params.ghost_state.theta; + *u = params.u; if (params.working == 1) return DD_GHOST_MOVING; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h index 93fc4ef..96a8241 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h @@ -98,11 +98,12 @@ uint8_t dd_add_bezier(float x_end, float y_end, float d1, float d2, float end_an /* * Return the current state of the followed ghost robot * - state : pointer to a robot_state_t structure where the ghost state will be written + * - u : pointer to a float in which to write the current value of the parameter on the spline * * return value : * - DD_GHOST_MOVING : if a trajectory is currently followed * - DD_GHOST_STOPPED : if the ghost robot is stopped */ -uint8_t dd_get_ghost_state(robot_state_t *state); +uint8_t dd_get_ghost_state(robot_state_t *state, float *u); #endif /* __DIFFERENTIAL_DRIVE_H */ hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-20 09:16:31
|
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 5f3e029aaab36e94eb061e83d3a810f3c6c3adce (commit) via 02e03abf2ff214556d7ec225b4837e0c42845bb8 (commit) via cb1cc4e6da65d34ec8d6b2cf7f045279265dc726 (commit) from d75c624ea6637e76d1acdc2f25ca59c8c93fc4c7 (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 5f3e029aaab36e94eb061e83d3a810f3c6c3adce Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 11:14:47 2011 +0200 [info] add a flag to CAN frames to tell whether they come from a card or from a program commit 02e03abf2ff214556d7ec225b4837e0c42845bb8 Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 10:10:30 2011 +0200 [krobot_monitor] show decoded CAN frames commit cb1cc4e6da65d34ec8d6b2cf7f045279265dc726 Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 10:00:47 2011 +0200 [info] make bezier trajectories continous ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/_oasis b/info/control2011/_oasis index 3b5b668..81dd9ef 100644 --- a/info/control2011/_oasis +++ b/info/control2011/_oasis @@ -98,8 +98,7 @@ Executable "krobot-dump-encoders" Executable "krobot-record" Path: src/tools - Install: false - Build: false + Install: true CompiledObject: best MainIs: krobot_record.ml BuildDepends: krobot, lwt.syntax diff --git a/info/control2011/setup.ml b/info/control2011/setup.ml index a90aa6e..9065940 100644 --- a/info/control2011/setup.ml +++ b/info/control2011/setup.ml @@ -1,7 +1,7 @@ (* setup.ml generated for the first time by OASIS v0.2.0~alpha1 *) (* OASIS_START *) -(* DO NOT EDIT (digest: e5aa81e40566663130f898cbaee3b839) *) +(* DO NOT EDIT (digest: f74f01087e7cdeda8c8d0d200fd9f844) *) (* Regenerated by OASIS v0.2.0 Visit http://oasis.forge.ocamlcore.org for more information and @@ -5568,8 +5568,8 @@ let setup_t = cs_plugin_data = []; }, { - bs_build = [(OASISExpr.EBool true, false)]; - bs_install = [(OASISExpr.EBool true, false)]; + bs_build = [(OASISExpr.EBool true, true)]; + bs_install = [(OASISExpr.EBool true, true)]; bs_path = "src/tools"; bs_compiled_object = Best; bs_build_depends = diff --git a/info/control2011/src/driver/krobot_driver.ml b/info/control2011/src/driver/krobot_driver.ml index 9e5b578..184dfe9 100644 --- a/info/control2011/src/driver/krobot_driver.ml +++ b/info/control2011/src/driver/krobot_driver.ml @@ -65,7 +65,7 @@ lwt () = | Kill "driver" -> exit 0 - | CAN frame -> begin + | CAN(Info, frame) -> begin match !can_opt with | Some can -> Krobot_can_bus.send can (ts, frame) @@ -86,7 +86,7 @@ lwt () = try_lwt while_lwt true do lwt (ts, frame) = Krobot_can_bus.recv can in - Krobot_bus.send bus (ts, CAN frame) + Krobot_bus.send bus (ts, CAN(Elec, frame)) done with exn -> (* Make sure no more messages are sent on the CAN bus. *) diff --git a/info/control2011/src/lib/krobot_bus.ml b/info/control2011/src/lib/krobot_bus.ml index a77f60e..8633395 100644 --- a/info/control2011/src/lib/krobot_bus.ml +++ b/info/control2011/src/lib/krobot_bus.ml @@ -18,8 +18,10 @@ let port = 50000 | Types | +-----------------------------------------------------------------+ *) +type frame_source = Elec | Info + type message = - | CAN of Krobot_can.frame + | CAN of frame_source * Krobot_can.frame | Log of string | Send | Kill of string @@ -50,9 +52,10 @@ let string_of_vector v = sprintf "{ vx = %f; vy = %f }" v.vx v.vy let string_of_message = function - | CAN frame -> + | CAN(source, frame) -> sprintf - "CAN %s" + "CAN(%s, %s)" + (match source with Elec -> "Elec" | Info -> "Info") (Krobot_can.string_of_frame frame) | Log str -> sprintf diff --git a/info/control2011/src/lib/krobot_bus.mli b/info/control2011/src/lib/krobot_bus.mli index dccfb9f..fb1333a 100644 --- a/info/control2011/src/lib/krobot_bus.mli +++ b/info/control2011/src/lib/krobot_bus.mli @@ -18,10 +18,13 @@ val get : unit -> t Lwt.t (** [get ()] returns the krobot bus. It exits the program on error. *) +type frame_source = Elec | Info + (** The source of CAN frames. *) + (** Type of message exchanged over the bus. *) type message = - | CAN of Krobot_can.frame - (** A CAN frame. *) + | CAN of frame_source * Krobot_can.frame + (** [CAN(source, frmae)] a CAN frame. *) | Log of string (** A log message. *) | Send diff --git a/info/control2011/src/lib/krobot_message.ml b/info/control2011/src/lib/krobot_message.ml index 94db4fc..93ee3f4 100644 --- a/info/control2011/src/lib/krobot_message.ml +++ b/info/control2011/src/lib/krobot_message.ml @@ -32,7 +32,7 @@ type t = | Motor_bezier of float * float * float * float * float * float | Motor_stop | Odometry of float * float * float - | Odometry_ghost of float * float * float * bool + | Odometry_ghost of float * float * float * int * bool | Set_odometry of float * float * float | Set_controller_mode of bool | Req_motor_status @@ -108,10 +108,10 @@ let to_string = function sprintf "Odometry(%f, %f, %f)" x y theta - | Odometry_ghost(x, y, theta, following) -> + | Odometry_ghost(x, y, theta, u, following) -> sprintf - "Odometry_ghost(%f, %f, %f, %B)" - x y theta following + "Odometry_ghost(%f, %f, %f, %d, %B)" + x y theta u following | Set_odometry(x, y, theta) -> sprintf "Set_odometry(%f, %f, %f)" @@ -191,12 +191,13 @@ let encode = function ~remote:false ~format:F29bits ~data - | Odometry_ghost(x, y, theta, following) -> - let data = String.create 7 in + | Odometry_ghost(x, y, theta, u, following) -> + let data = String.create 8 in put_sint16 data 0 (truncate (x *. 1000.)); put_sint16 data 2 (truncate (y *. 1000.)); put_sint16 data 4 (truncate (theta *. 10000.)); - put_uint8 data 6 (if following then 1 else 0); + put_uint8 data 6 u; + put_uint8 data 7 (if following then 1 else 0); frame ~identifier:105 ~kind:Data @@ -375,7 +376,8 @@ let decode frame = (float (get_sint16 frame.data 0) /. 1000., float (get_sint16 frame.data 2) /. 1000., float (get_sint16 frame.data 4) /. 10000., - get_uint8 frame.data 6 <> 0) + get_uint8 frame.data 6, + get_uint8 frame.data 7 <> 0) | 201 -> Motor_move (float (get_sint32 frame.data 0) /. 1000., @@ -439,13 +441,12 @@ let decode frame = +-----------------------------------------------------------------+ *) let send bus (timestamp, msg) = - Krobot_bus.send bus (timestamp, Krobot_bus.CAN(encode msg)) - + Krobot_bus.send bus (timestamp, Krobot_bus.CAN(Krobot_bus.Info, encode msg)) let recv bus = E.fmap (fun (timestamp, message) -> match message with - | Krobot_bus.CAN frame -> + | Krobot_bus.CAN(_, frame) -> Some(timestamp, decode frame) | _ -> None) diff --git a/info/control2011/src/lib/krobot_message.mli b/info/control2011/src/lib/krobot_message.mli index 53df1d6..c17cb0b 100644 --- a/info/control2011/src/lib/krobot_message.mli +++ b/info/control2011/src/lib/krobot_message.mli @@ -51,7 +51,7 @@ type t = | Odometry of float * float * float (** [Odometry(x, y, theta)] the position of the robot on the table. *) - | Odometry_ghost of float * float * float * bool + | Odometry_ghost of float * float * float * int * bool (** [Odometry_ghost(x, y, theta, following)]. [following] is [true] iff the robot is following the ghost. *) | Set_odometry of float * float * float diff --git a/info/control2011/src/tools/krobot_dump.ml b/info/control2011/src/tools/krobot_dump.ml index 1715ca5..4b75d21 100644 --- a/info/control2011/src/tools/krobot_dump.ml +++ b/info/control2011/src/tools/krobot_dump.ml @@ -11,6 +11,7 @@ open Lwt open Lwt_react +open Krobot_bus let raw = ref false let decoded = ref true @@ -60,9 +61,9 @@ lwt () = (E.map_s (fun (timestamp, message) -> match message with - | Krobot_bus.CAN frame -> + | CAN(source, frame) -> let msg = Krobot_message.decode frame in - lwt () = Lwt_io.print (date_string timestamp)in + lwt () = Lwt_io.printf "%s| %s" (match source with Elec -> "elec" | Info -> "info") (date_string timestamp)in lwt () = if !decoded then Lwt_io.printf ": %s" (Krobot_message.to_string msg) diff --git a/info/control2011/src/tools/krobot_monitor.ml b/info/control2011/src/tools/krobot_monitor.ml index 0fae3c7..81f529e 100644 --- a/info/control2011/src/tools/krobot_monitor.ml +++ b/info/control2011/src/tools/krobot_monitor.ml @@ -11,6 +11,7 @@ open Lwt open Lwt_react +open Krobot_bus let date_string time = let tm = Unix.localtime time in @@ -45,7 +46,16 @@ lwt () = E.keep (E.map_s (fun (timestamp, message) -> - Lwt_io.printlf "%s: %s" (date_string timestamp) (Krobot_bus.string_of_message message)) + match message with + | CAN(_, frame) -> + Lwt_io.printlf "%s: %s -> %s" + (date_string timestamp) + (Krobot_bus.string_of_message message) + (Krobot_message.to_string (Krobot_message.decode frame)) + | _ -> + Lwt_io.printlf "%s: %s" + (date_string timestamp) + (Krobot_bus.string_of_message message)) (Krobot_bus.recv bus)); fst (wait ()) diff --git a/info/control2011/src/tools/krobot_planner.ml b/info/control2011/src/tools/krobot_planner.ml index 0dbe9f7..dec418e 100644 --- a/info/control2011/src/tools/krobot_planner.ml +++ b/info/control2011/src/tools/krobot_planner.ml @@ -52,6 +52,10 @@ type planner = { mutable motors_moving : bool; (* Are the motor currently active ? *) + mutable curve_status : int; + (* The status of the trajectory controller on the curve (between 0 + and 255). *) + mutable mover : unit Lwt.t; (* The thread moving the robot. *) @@ -125,90 +129,147 @@ let wait_done planner = lwt () = Lwt_unix.sleep 0.3 in lwt () = while_lwt planner.motors_moving do - Lwt_unix.sleep 0.2 + Lwt_unix.sleep 0.1 done in Lwt_log.info "trajectory done" +let wait_middle planner = + lwt () = Lwt_log.info "waiting for the robot to be in the middle of the trajectory" in + lwt () = Lwt_unix.sleep 0.3 in + lwt () = + while_lwt planner.curve_status < 128 do + Lwt_unix.sleep 0.001 + done + in + Lwt_log.info "robot in the middle of the trajectory" + +let wait_start planner = + lwt () = Lwt_log.info "waiting for the robot to start the new trajectory" in + lwt () = + while_lwt planner.curve_status >= 128 do + Lwt_unix.sleep 0.001 + done + in + Lwt_log.info "robot started the new trajectory" + let go planner rotation_speed rotation_acceleration moving_speed moving_acceleration = if planner.moving then return () else begin -(* let rec loop () = - match S.value planner.vertices with - | { x; y } :: rest -> - let sqr x = x *. x in - let radius = sqrt (sqr (max wheels_position (robot_size -. wheels_position)) +. sqr (robot_size /. 2.)) in - if x >= radius && x <= world_width -. radius && y >= radius && y <= world_height -. radius then begin - (* Turn the robot. *) - let alpha = math_mod_float (atan2 (y -. planner.position.y) (x -. planner.position.x) -. planner.orientation) (2. *. pi) in - lwt () = Lwt_log.info_f "turning by %f radians" alpha in - lwt () = Krobot_message.send planner.bus (Unix.gettimeofday (), - Motor_turn(alpha, - rotation_speed, - rotation_acceleration)) in - lwt () = wait_done planner in - - (* Move the robot. *) - let dist = sqrt (sqr (x -. planner.position.x) +. sqr (y -. planner.position.y)) in - lwt () = Lwt_log.info_f "moving by %f meters" dist in - lwt () = Krobot_message.send planner.bus (Unix.gettimeofday (), - Motor_move(dist, - moving_speed, - moving_acceleration)) in - lwt () = wait_done planner in - - (* Remove the point. *) - (match S.value planner.vertices with - | _ :: l -> planner.set_vertices l - | [] -> ()); - planner.set_origin (planner.position, - { vx = cos planner.orientation; - vy = sin planner.orientation }); - - loop () - end else - Lwt_log.warning_f "can not move to (%f, %f)" x y - | [] -> - return () - in*) + (* let rec loop () = + match S.value planner.vertices with + | { x; y } :: rest -> + let sqr x = x *. x in + let radius = sqrt (sqr (max wheels_position (robot_size -. wheels_position)) +. sqr (robot_size /. 2.)) in + if x >= radius && x <= world_width -. radius && y >= radius && y <= world_height -. radius then begin + (* Turn the robot. *) + let alpha = math_mod_float (atan2 (y -. planner.position.y) (x -. planner.position.x) -. planner.orientation) (2. *. pi) in + lwt () = Lwt_log.info_f "turning by %f radians" alpha in + lwt () = Krobot_message.send planner.bus (Unix.gettimeofday (), + Motor_turn(alpha, + rotation_speed, + rotation_acceleration)) in + lwt () = wait_done planner in + + (* Move the robot. *) + let dist = sqrt (sqr (x -. planner.position.x) +. sqr (y -. planner.position.y)) in + lwt () = Lwt_log.info_f "moving by %f meters" dist in + lwt () = Krobot_message.send planner.bus (Unix.gettimeofday (), + Motor_move(dist, + moving_speed, + moving_acceleration)) in + lwt () = wait_done planner in + + (* Remove the point. *) + (match S.value planner.vertices with + | _ :: l -> planner.set_vertices l + | [] -> ()); + planner.set_origin (planner.position, + { vx = cos planner.orientation; + vy = sin planner.orientation }); + + loop () + end else + Lwt_log.warning_f "can not move to (%f, %f)" x y + | [] -> + return () + in*) set_moving planner true; planner.mover <- ( try_lwt let o, v = planner.origin in + + (* Compute all cubic bezier curves. *) let params = List.rev (Bezier.fold_vertices (fun p q r s acc -> (p, q, r, s) :: acc) v (o :: planner.vertices) []) in - Lwt_list.iter_s - (fun (p, q, r, s) -> - - let v = vector r s in - lwt () = - Krobot_message.send - planner.bus - (Unix.gettimeofday (), - Motor_bezier(s.x, - s.y, - distance p q, - distance r s, - atan2 v.vy v.vx, - 0.)) - in - - lwt () = wait_done planner in - - (match planner.vertices with - | _ :: l -> - set_vertices planner l - | [] -> - ()); - set_origin planner (planner.position, - { vx = cos planner.orientation; - vy = sin planner.orientation }); - - return () - ) - params + + (* Send a bezier curve to the robot. *) + let send_curve (p, q, r, s) v_end = + (* Compute parameters. *) + let d1 = distance p q and d2 = distance r s in + let v = vector r s in + let theta_end = atan2 v.vy v.vx in + + ignore ( + Lwt_log.info_f + "sending bezier curve, x = %f, y = %f, d1 = %f, d2 = %f, theta_end = %f, v_end = %f" + s.x s.y d1 d2 theta_end v_end + ); + + (* Send the curve. *) + Krobot_message.send planner.bus (Unix.gettimeofday (), Motor_bezier(s.x, s.y, d1, d2, theta_end, v_end)) + in + + (* Remove the first vertice of the trajecotry. *) + let drop_vertice () = + (match planner.vertices with + | _ :: l -> + set_vertices planner l + | [] -> + ()); + set_origin planner (planner.position, + { vx = cos planner.orientation; + vy = sin planner.orientation }) + in + + let rec loop = function + | [] -> + lwt () = wait_done planner in + drop_vertice (); + return () + + | [points] -> + lwt () = wait_middle planner in + lwt () = send_curve points 0.01 in + lwt () = wait_done planner in + drop_vertice (); + return () + + | points :: rest -> + lwt () = wait_middle planner in + lwt () = send_curve points 0.5 in + lwt () = wait_start planner in + drop_vertice (); + loop rest + in + + match params with + | [] -> + return () + + | [points] -> + lwt () = send_curve points 0.01 in + lwt () = wait_done planner in + drop_vertice (); + return () + + | points :: rest -> + lwt () = send_curve points 0.5 in + loop rest + with exn -> Lwt_log.error_f ~section ~exn "failed to move" + finally set_moving planner false; return () @@ -222,7 +283,7 @@ let go planner rotation_speed rotation_acceleration moving_speed moving_accelera let handle_message planner (timestamp, message) = match message with - | CAN frame -> begin + | CAN(_, frame) -> begin match decode frame with | Odometry(x, y, theta) -> planner.position <- { x; y }; @@ -232,7 +293,8 @@ let handle_message planner (timestamp, message) = { vx = cos planner.orientation; vy = sin planner.orientation }) - | Odometry_ghost(x, y, theta, following) -> + | Odometry_ghost(x, y, theta, u, following) -> + planner.curve_status <- u; planner.motors_moving <- following | _ -> @@ -313,6 +375,7 @@ lwt () = vertices = []; moving = false; motors_moving = false; + curve_status = 0; mover = return (); position = { x = 0.; y = 0. }; orientation = 0.; diff --git a/info/control2011/src/tools/krobot_record.ml b/info/control2011/src/tools/krobot_record.ml index f0a7d72..29bc65a 100644 --- a/info/control2011/src/tools/krobot_record.ml +++ b/info/control2011/src/tools/krobot_record.ml @@ -11,6 +11,7 @@ open Lwt open Lwt_react +open Krobot_bus lwt () = if Array.length Sys.argv <> 2 then begin @@ -21,13 +22,16 @@ lwt () = lwt bus = Krobot_bus.get () in lwt oc = Lwt_io.open_file ~mode:Lwt_io.output Sys.argv.(1) in - (* The proxy for the driver. *) - let driver = OBus_proxy.make (OBus_peer.make (Krobot_bus.to_bus bus) "fr.krobot.Service.Driver") ["fr"; "krobot"; "CAN"] in - - (* Receive frames comming from the driver. *) - lwt ev = OBus_signal.connect (OBus_signal.make Krobot_interface_can.Fr_krobot_CAN.s_message driver) in - - (* Write all frames to the output file. *) - E.keep (E.map_s (fun v -> Lwt_io.write_value oc (Krobot_can.frame_of_tuple v)) ev); + (* Write all frames comming from the electronic to the output + file. *) + E.keep + (E.map_s + (fun (timestamp, message) -> + match message with + | CAN(Elec, frame) -> + Lwt_io.write_value oc (timestamp, frame) + | _ -> + return ()) + (Krobot_bus.recv bus)); fst (wait ()) diff --git a/info/control2011/src/tools/krobot_replay.ml b/info/control2011/src/tools/krobot_replay.ml index 73284bb..f1c96e4 100644 --- a/info/control2011/src/tools/krobot_replay.ml +++ b/info/control2011/src/tools/krobot_replay.ml @@ -16,7 +16,7 @@ open Krobot_bus let rec loop bus ic prev_timestamp = lwt timestamp, frame = Lwt_io.read_value ic in lwt () = Lwt_unix.sleep (timestamp -. prev_timestamp) in - lwt () = Krobot_bus.send bus (Unix.gettimeofday (), CAN frame) in + lwt () = Krobot_bus.send bus (Unix.gettimeofday (), CAN(Elec, frame)) in loop bus ic timestamp lwt () = @@ -30,7 +30,7 @@ lwt () = try_lwt lwt timestamp, frame = Lwt_io.read_value ic in - lwt () = Krobot_bus.send bus (Unix.gettimeofday (), CAN frame) in + lwt () = Krobot_bus.send bus (Unix.gettimeofday (), CAN(Elec, frame)) in loop bus ic timestamp with End_of_file -> Lwt_io.close ic diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index a79ddea..9e22445 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -326,7 +326,7 @@ let simplify viewer = let handle_message viewer (timestamp, message) = match message with - | CAN frame -> begin + | CAN(_, frame) -> begin match decode frame with | Odometry(x, y, theta) -> let angle = math_mod_float (theta) (2. *. pi) in @@ -339,7 +339,7 @@ let handle_message viewer (timestamp, message) = queue_draw viewer end - | Odometry_ghost(x, y, theta, following) -> + | Odometry_ghost(x, y, theta, u, following) -> let angle = math_mod_float (theta) (2. *. pi) in let ghost = { pos = { x; y }; theta = angle } in if ghost <> viewer.ghost then begin hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-20 07:04:43
|
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 d75c624ea6637e76d1acdc2f25ca59c8c93fc4c7 (commit) from fa1824d9c5b53f71a4e6091206ab2e73ac1c1b74 (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 d75c624ea6637e76d1acdc2f25ca59c8c93fc4c7 Author: Jérémie Dimino <je...@di...> Date: Wed Apr 20 09:03:13 2011 +0200 [krobot_hub] fix a race condition which prevented the hub to be run in background ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_hub.ml b/info/control2011/src/tools/krobot_hub.ml index 406e505..e68fc5b 100644 --- a/info/control2011/src/tools/krobot_hub.ml +++ b/info/control2011/src/tools/krobot_hub.ml @@ -136,11 +136,11 @@ lwt () = (* Establish the local server. *) ignore (Lwt_io.establish_server (Unix.ADDR_INET(Unix.inet_addr_any, port)) (fun channels -> handle_connection hub channels)); - (* Launch link to other HUBs. *) - List.iter (fun host -> ignore (link hub host)) !hosts; - (* Fork if not prevented. *) if !fork then Lwt_daemon.daemonize (); + (* Launch link to other HUBs. *) + List.iter (fun host -> ignore (link hub host)) !hosts; + (* Wait forever. *) fst (wait ()) hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 19:12:50
|
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 fa1824d9c5b53f71a4e6091206ab2e73ac1c1b74 (commit) from 8359d44c2c097a6a9851638a1f67524dd4d3bd2c (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 fa1824d9c5b53f71a4e6091206ab2e73ac1c1b74 Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 21:11:38 2011 +0200 [info] add krobot-monitor ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/_oasis b/info/control2011/_oasis index e826386..3b5b668 100644 --- a/info/control2011/_oasis +++ b/info/control2011/_oasis @@ -82,6 +82,13 @@ Executable "krobot-dump" MainIs: krobot_dump.ml BuildDepends: krobot, lwt.syntax +Executable "krobot-monitor" + Path: src/tools + Install: true + CompiledObject: best + MainIs: krobot_monitor.ml + BuildDepends: krobot, lwt.syntax + Executable "krobot-dump-encoders" Path: src/tools Install: true diff --git a/info/control2011/_tags b/info/control2011/_tags index 0faf3ef..42135ad 100644 --- a/info/control2011/_tags +++ b/info/control2011/_tags @@ -2,7 +2,7 @@ <src/interfaces/*.ml>: -syntax_camlp4o # OASIS_START -# DO NOT EDIT (digest: c856ca92c511128600c4a9a2ddb551e7) +# DO NOT EDIT (digest: e0fdca06da598f490f540bfd1de2f7ad) # Library krobot "src/lib": include "src/lib/krobot.cmxs": use_krobot @@ -55,6 +55,11 @@ <src/tools/krobot_viewer.{native,byte}>: pkg_lablgtk2.glade <src/tools/krobot_viewer.{native,byte}>: pkg_cairo.lablgtk2 <src/tools/*.ml{,i}>: pkg_lablgtk2.glade +# Executable krobot-monitor +<src/tools/krobot_monitor.{native,byte}>: use_krobot +<src/tools/krobot_monitor.{native,byte}>: pkg_lwt.unix +<src/tools/krobot_monitor.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_monitor.{native,byte}>: pkg_lwt.react # Executable krobot-hil-simulator <src/tools/krobot_hil_simulator.{native,byte}>: use_krobot <src/tools/krobot_hil_simulator.{native,byte}>: pkg_lwt.unix diff --git a/info/control2011/setup.ml b/info/control2011/setup.ml index 41e82e4..a90aa6e 100644 --- a/info/control2011/setup.ml +++ b/info/control2011/setup.ml @@ -1,7 +1,7 @@ (* setup.ml generated for the first time by OASIS v0.2.0~alpha1 *) (* OASIS_START *) -(* DO NOT EDIT (digest: d57b3cf1b9ea66ae670ea790a42da492) *) +(* DO NOT EDIT (digest: e5aa81e40566663130f898cbaee3b839) *) (* Regenerated by OASIS v0.2.0 Visit http://oasis.forge.ocamlcore.org for more information and @@ -5292,6 +5292,34 @@ let setup_t = {exec_custom = false; exec_main_is = "krobot_viewer.ml"; }); Executable ({ + cs_name = "krobot-monitor"; + cs_data = PropList.Data.create (); + cs_plugin_data = []; + }, + { + bs_build = [(OASISExpr.EBool true, true)]; + bs_install = [(OASISExpr.EBool true, true)]; + bs_path = "src/tools"; + bs_compiled_object = Best; + bs_build_depends = + [ + InternalLibrary "krobot"; + FindlibPackage ("lwt.syntax", None) + ]; + bs_build_tools = [ExternalTool "ocamlbuild"]; + bs_c_sources = []; + bs_data_files = []; + bs_ccopt = [(OASISExpr.EBool true, [])]; + bs_cclib = [(OASISExpr.EBool true, [])]; + bs_dlllib = [(OASISExpr.EBool true, [])]; + bs_dllpath = [(OASISExpr.EBool true, [])]; + bs_byteopt = [(OASISExpr.EBool true, [])]; + bs_nativeopt = [(OASISExpr.EBool true, [])]; + }, + {exec_custom = false; exec_main_is = "krobot_monitor.ml"; + }); + Executable + ({ cs_name = "krobot-hil-simulator"; cs_data = PropList.Data.create (); cs_plugin_data = []; diff --git a/info/control2011/src/tools/krobot_monitor.ml b/info/control2011/src/tools/krobot_monitor.ml new file mode 100644 index 0000000..0fae3c7 --- /dev/null +++ b/info/control2011/src/tools/krobot_monitor.ml @@ -0,0 +1,52 @@ +(* + * krobot_monitor.ml + * ----------------- + * Copyright : (c) 2011, Jeremie Dimino <je...@di...> + * Licence : BSD3 + * + * This file is a part of [kro]bot. + *) + +(* Monitor all messages passing on the krobot bus. *) + +open Lwt +open Lwt_react + +let date_string time = + let tm = Unix.localtime time in + let month_string = + match tm.Unix.tm_mon with + | 0 -> "Jan" + | 1 -> "Feb" + | 2 -> "Mar" + | 3 -> "Apr" + | 4 -> "May" + | 5 -> "Jun" + | 6 -> "Jul" + | 7 -> "Aug" + | 8 -> "Sep" + | 9 -> "Oct" + | 10 -> "Nov" + | 11 -> "Dec" + | _ -> Printf.ksprintf failwith "Lwt_log.ascdate: invalid month, %d" tm.Unix.tm_mon + in + Printf.sprintf + "%s %2d %02d:%02d:%02d.%s" + month_string + tm.Unix.tm_mday + tm.Unix.tm_hour + tm.Unix.tm_min + tm.Unix.tm_sec + (String.sub (Printf.sprintf "%.4f" (fst (modf time))) 2 4) + +lwt () = + lwt bus = Krobot_bus.get () in + + E.keep + (E.map_s + (fun (timestamp, message) -> + Lwt_io.printlf "%s: %s" (date_string timestamp) (Krobot_bus.string_of_message message)) + (Krobot_bus.recv bus)); + + fst (wait ()) + hooks/post-receive -- krobot |
From: Xavier L. <Ba...@us...> - 2011-04-19 19:09:47
|
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 8359d44c2c097a6a9851638a1f67524dd4d3bd2c (commit) via b4c4f022e4d1ac4d4fc0935340e488090892cdb0 (commit) via 98a0d66534cc7697ad707c6d418496183fcc5606 (commit) from 4f1a9587a1dba18c3bd3e3b962dacaffab58c2db (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 8359d44c2c097a6a9851638a1f67524dd4d3bd2c Author: Xavier Lagorce <Xav...@cr...> Date: Tue Apr 19 20:52:04 2011 +0200 [Controller_Motor_STM32] One thread to send them all. commit b4c4f022e4d1ac4d4fc0935340e488090892cdb0 Author: Xavier Lagorce <Xav...@cr...> Date: Tue Apr 19 16:48:12 2011 +0200 [Controller_Motor_STM32] Extended differential drive controller with Bezier Splines. The differential drive controller can now follow some Bezier Splines. The splines are directly generated on the ARM and only global parameters are required. This currently support to chain splines but not to interrupt them. commit 98a0d66534cc7697ad707c6d418496183fcc5606 Author: Xavier Lagorce <Xav...@cr...> Date: Tue Apr 19 16:43:00 2011 +0200 [Controller_Motor_STM32] Added a function to trajectory_controller to allow direct action on speed. ----------------------------------------------------------------------- Changes: diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c new file mode 100644 index 0000000..0b74fde --- /dev/null +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.c @@ -0,0 +1,122 @@ +/* + * bezier_utils.c + * -------------- + * Copyright : (c) 2011, Xavier Lagorce <Xav...@cr...> + * Licence : BSD3 + * + * This file is a part of [kro]bot. + */ + +#include "bezier_utils.h" + +float bezier_apply(float params[4], float u) { + return (params[0] + params[1]*u + params[2]*u*u + params[3]*u*u*u); +} + +void bezier_generate(float params[2][4], + float p_x, float p_y, + float p1_x, float p1_y, + float p2_x, float p2_y, + float s_x, float s_y) { + + params[0][0] = p_x; + params[1][0] = p_y; + params[0][1] = -3*p_x+3*p1_x; + params[1][1] = -3*p_y+3*p1_y; + params[0][2] = 3*p_x-6*p1_x+3*p2_x; + params[1][2] = 3*p_y-6*p1_y+3*p2_y; + params[0][3] = -p_x+3*p1_x-3*p2_x+s_x; + params[1][3] = -p_y+3*p1_y-3*p2_y+s_y; +} + +void bezier_velocity_profile(float dparams[2][4], float ddparams[2][4], + float v_max, float at_max, float ar_max, + float v_ini, float v_end, + float du, float* v_tab) { + float vmins[4], cr, cr_p, cr_pp, u, vm, dt, nv, dx, dy, dsu; + int ind = 0, j, nb_pts, mins[4], im, i; + + for (i=0, u=0.0; u <= 1.0; i++, u+=du) { + v_tab[i] = v_max; + } + nb_pts = i; + + // Looking for curvature radius minima to limit speed at this positions + mins[ind] = 0; + vmins[ind] = v_ini; + ind++; + + cr_pp = fabsf(bezier_cr(0, dparams, ddparams)); + cr_p = fabsf(bezier_cr(du, dparams, ddparams)); + for (i=2, u=2*du; u <= 1.0; i++, u+=du) { + cr = fabsf(bezier_cr(u, dparams, ddparams)); + if ((cr >= cr_p) && (cr_p < cr_pp)) { + mins[ind] = i; + vmins[ind] = sqrtf(ar_max*cr); + ind++; + } + cr_pp = cr_p; + cr_p = cr; + } + mins[ind] = nb_pts-1; + vmins[ind] = v_end; + ind++; + + // Compute speed limitations + for (j=0; j < ind; j++) { + im = mins[j]; + vm = vmins[j]; + if (vm < v_max) { + v_tab[im] = vm; + + // Profile for preceding velocity + for (i = im-1; i >= 0; i--) { + dx = bezier_apply(dparams[0], du*(i+1)); + dy = bezier_apply(dparams[1], du*(i+1)); + dsu = sqrtf(dx*dx + dy*dy); + dt = (-v_tab[i+1]+sqrtf(v_tab[i+1]*v_tab[i+1]+2*at_max*du*dsu))/at_max; + nv = v_tab[i+1]+at_max*dt; + if (nv < v_tab[i]) { + v_tab[i] = nv; + } else { + break; + } + } + // Profile for following sector + for (i = im+1; i < nb_pts; i++) { + dx = bezier_apply(dparams[0], du*(i-1)); + dy = bezier_apply(dparams[1], du*(i-1)); + dsu = sqrtf(dx*dx + dy*dy); + dt = (-v_tab[i-1]+sqrtf(v_tab[i-1]*v_tab[i-1]+2*at_max*du*dsu))/at_max; + nv = v_tab[i-1]+at_max*dt; + if (nv < v_tab[i]) { + v_tab[i] = nv; + } else { + break; + } + } + } // end if (vm < v_max) + } // for mins +} + +float bezier_cr(float u, float dparams[2][4], float ddparams[2][4]) { + + float dx, dy, ddx, ddy; + + dx = bezier_apply(dparams[0], u); + dy = bezier_apply(dparams[1], u); + ddx = bezier_apply(ddparams[0], u); + ddy = bezier_apply(ddparams[1], u); + + return powf(dx*dx+dy*dy, 1.5) / (dx*ddy - dy*ddx); +} + +void bezier_diff(float params[2][4], float dparams[2][4]) { + int i, j; + for (i=0; i<=1; i++) { + for (j=0; j<=2; j++) { + dparams[i][j] = (j+1)*params[i][j+1]; + } + dparams[i][3] = 0.; + } +} diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h new file mode 100644 index 0000000..c36fd62 --- /dev/null +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/bezier_utils.h @@ -0,0 +1,50 @@ +/* + * bezier_utils.h + * -------------- + * Copyright : (c) 2011, Xavier Lagorce <Xav...@cr...> + * Licence : BSD3 + * + * This file is a part of [kro]bot. + */ + +#ifndef __BEZIER_UTILS_H +#define __BEZIER_UTILS_H + +#include <math.h> +#include <stdint.h> + +/* + * Apply a polynomial form of a Bezier Spline to a value of the parameter + */ +float bezier_apply(float params[4], float u); + +/* + * Computes the parameters of the polynomial from of a Bezier Spline + */ +void bezier_generate(float params[2][4], + float p_x, float p_y, + float p1_x, float p1_y, + float p2_x, float p2_y, + float s_x, float s_y); + +/* + * Computes the velocity profile along a Bezier Spline and according to physical + * contraints + */ +void bezier_velocity_profile(float dparams[2][4], float ddparams[2][4], + float v_max, float at_max, float ar_max, + float v_ini, float v_end, + float du, float* v_tab); + +/* + * Computes the curvature radius of a Bezier Spline for a given value of the + * parameter + */ +float bezier_cr(float u, float dparams[2][4], float ddparams[2][4]); + +/* + * Differentiates the polynomial form of a Bezier Spline + */ +void bezier_diff(float params[2][4], float dparams[2][4]); + +#endif /* __BEZIER_UTILS_H */ diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h new file mode 100644 index 0000000..9980947 --- /dev/null +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_messages.h @@ -0,0 +1,164 @@ +/* + * can_messages.h + * -------------- + * Copyright : (c) 2011, Xavier Lagorce <Xav...@cr...> + * Licence : BSD3 + * + * This file is a part of [kro]bot. + */ + +#ifndef __CAN_MESSAGES_H +#define __CAN_MESSAGES_H + +#include <stdint.h> + +/* +-----------------------------------------------------------------+ + | CAN messages IDs | + +-----------------------------------------------------------------+ */ + +// Data sent by the card +#define CAN_MSG_ENCODERS34 100 // encoder_can_msg_t +#define CAN_MSG_MOTOR3 101 // motor_can_msg_t +#define CAN_MSG_MOTOR4 102 // motor_can_msg_t +#define CAN_MSG_STATUS 103 // status_can_msg_t +#define CAN_MSG_ODOMETRY 104 // odometry_can_msg_t +#define CAN_MSG_GHOST 105 // ghost_can_msg_t + +// Received commands +#define CAN_MSG_MOVE 201 // move_can_msg_t +#define CAN_MSG_TURN 202 // turn_can_msg_t +#define CAN_MSG_ODOMETRY_SET 203 // odometry_can_msg_t +#define CAN_MSG_STOP 204 // stop_can_msg_t +#define CAN_MSG_CONTROLLER_MODE 205 // controller_mode_can_msg_t +#define CAN_MSG_BEZIER_ADD 206 // bezier_can_msg_t + +/* +-----------------------------------------------------------------+ + | CAN messages data structures | + +-----------------------------------------------------------------+ */ + +// Information about two encoders +typedef struct { + uint16_t encoder1_pos __attribute__((__packed__)); + uint16_t encoder2_pos __attribute__((__packed__)); + uint8_t encoder1_dir; + uint8_t encoder2_dir; + uint16_t padding __attribute__((__packed__)); +} encoder_msg_t; + +// Position and speed of one controller motor +typedef struct { + float position __attribute__((__packed__)); // angle in radians + float speed __attribute__((__packed__)); // speed in rad/s (estimation) +} motor_msg_t; + +// Trajectory controller states +typedef struct { + uint8_t is_moving; +} status_msg_t; + +// Robot state +typedef struct { + int16_t x __attribute__((__packed__)); // X position in mm (fixed point representation...) + int16_t y __attribute__((__packed__)); // Y position in mm + int16_t theta __attribute__((__packed__)); // angle in 1/10000 radians +} odometry_msg_t; + +// Ghost state for differential drive system +typedef struct { + int16_t x __attribute__((__packed__)); // X position in mm (fixed point representation...) + int16_t y __attribute__((__packed__)); // Y position in mm + int16_t theta __attribute__((__packed__)); // angle in 1/10000 radians + uint8_t state; // 1 if trajectory in progress, 0 else +} ghost_msg_t; + +// Move command +typedef struct { + int32_t distance __attribute__((__packed__)); // Distance in mm (fixed point representation...) + uint16_t speed __attribute__((__packed__)); // Speed in mm/s + uint16_t acceleration __attribute__((__packed__)); // Acceleration in mm/s^2 +} move_msg_t; + +// Turn command +typedef struct { + int32_t angle __attribute__((__packed__)); // angle in 1/10000 radians (fixed point representation...) + uint16_t speed __attribute__((__packed__)); // Speed in 1/1000 rad/s + uint16_t acceleration __attribute__((__packed__)); // Acceleration in 1/1000 radians/s^2 +} turn_msg_t; + +// Add a new Bezier Spline to the wait queue +typedef struct { + uint16_t x_end:12 __attribute__((__packed__)); // end point x coordinate in mm + uint16_t y_end:12 __attribute__((__packed__)); // end point y coordinate in mm + uint8_t d1; // first branch length in cm + uint8_t d2; // last branch length in cm + int16_t theta_end:13 __attribute__((__packed__)); // end angle in 1/1000 radians + uint16_t v_end:11 __attribute__((__packed__)); // final speed in mm/s +} bezier_msg_t; + +// Emergency stop +typedef struct { + uint8_t stop; // stop everything +} stop_msg_t; + +// Select robot mode (normal or HIL) +typedef struct { + uint8_t mode; +} controller_mode_msg_t; + + +/* +-----------------------------------------------------------------+ + | CAN messages unions for data representation | + +-----------------------------------------------------------------+ */ + +typedef union { + encoder_msg_t data; + uint32_t data32[2]; +} encoder_can_msg_t; + +typedef union { + motor_msg_t data; + uint32_t data32[2]; +} motor_can_msg_t; + +typedef union { + status_msg_t data; + uint32_t data32[2]; +} status_can_msg_t; + +typedef union { + odometry_msg_t data; + uint32_t data32[2]; +} odometry_can_msg_t; + +typedef union { + ghost_msg_t data; + uint32_t data32[2]; +} ghost_can_msg_t; + +typedef union { + move_msg_t data; + uint32_t data32[2]; +} move_can_msg_t; + +typedef union { + turn_msg_t data; + uint32_t data32[2]; +} turn_can_msg_t; + +typedef union { + bezier_msg_t data; + uint32_t data32[2]; +} bezier_can_msg_t; + +typedef union { + stop_msg_t data; + uint32_t data32[2]; +} stop_can_msg_t; + +typedef union { + controller_mode_msg_t data; + uint32_t data32[2]; +} controller_mode_can_msg_t; + + +#endif /* __CAN_MESSAGES_H */ diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c index 2c0e6da..9a86272 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.c @@ -19,103 +19,6 @@ PROC_DEFINE_STACK(stack_can_receive, KERN_MINSTACKSIZE * 8); // globals volatile uint8_t mode; -// Structures to represent data into CAN messages -typedef struct { - uint16_t encoder1_pos __attribute__((__packed__)); - uint16_t encoder2_pos __attribute__((__packed__)); - uint8_t encoder1_dir; - uint8_t encoder2_dir; - uint16_t padding __attribute__((__packed__)); -} encoder_msg_t; - -typedef struct { - float position __attribute__((__packed__)); - float speed __attribute__((__packed__)); -} motor_msg_t; - -typedef struct { - uint8_t is_moving; // 1 if a movement action is in progress, 0 if it's finished -} status_msg_t; - -typedef struct { - int16_t x __attribute__((__packed__)); // X position in mm (fixed point representation...) - int16_t y __attribute__((__packed__)); // Y position in mm - int16_t theta __attribute__((__packed__)); // angle in 1/10000 radians -} odometry_msg_t; - -typedef struct { - int32_t distance __attribute__((__packed__)); // Distance in mm (fixed point representation...) - uint16_t speed __attribute__((__packed__)); // Speed in mm/s - uint16_t acceleration __attribute__((__packed__)); // Acceleration in mm/s^2 -} move_msg_t; - -typedef struct { - int32_t angle __attribute__((__packed__)); // angle in 1/10000 radians (fixed point representation...) - uint16_t speed __attribute__((__packed__)); // Speed in 1/1000 rad/s - uint16_t acceleration __attribute__((__packed__)); // Acceleration in 1/1000 radians/s^2 -} turn_msg_t; - -typedef struct { - uint8_t stop; // stop everything -} stop_msg_t; - -typedef struct { - uint8_t mode; -} controller_mode_msg_t; - -// Union to manipulate CAN messages' data easily -typedef union { - encoder_msg_t data; - uint32_t data32[2]; -} encoder_can_msg_t; - -typedef union { - motor_msg_t data; - uint32_t data32[2]; -} motor_can_msg_t; - -typedef union { - status_msg_t data; - uint32_t data32[2]; -} status_can_msg_t; - -typedef union { - odometry_msg_t data; - uint32_t data32[2]; -} odometry_can_msg_t; - -typedef union { - move_msg_t data; - uint32_t data32[2]; -} move_can_msg_t; - -typedef union { - turn_msg_t data; - uint32_t data32[2]; -} turn_can_msg_t; - -typedef union { - stop_msg_t data; - uint32_t data32[2]; -} stop_can_msg_t; - -typedef union { - controller_mode_msg_t data; - uint32_t data32[2]; -} controller_mode_can_msg_t; - -// Can messages IDs -#define CAN_MSG_ENCODERS34 100 // encoder_can_msg_t -#define CAN_MSG_MOTOR3 101 // motor_can_msg_t -#define CAN_MSG_MOTOR4 102 // motor_can_msg_t -#define CAN_MSG_STATUS 103 // status_can_msg_t -#define CAN_MSG_ODOMETRY 104 // odometry_can_msg_t -#define CAN_MSG_MOVE 201 // move_can_msg_t -#define CAN_MSG_TURN 202 // turn_can_msg_t -#define CAN_MSG_ODOMETRY_SET 203 // odometry_can_msg_t -#define CAN_MSG_STOP 204 // stop_can_msg_t -#define CAN_MSG_CONTROLLER_MODE 205 // controller_mode_msg_t - // Process for communication static void NORETURN canMonitor_process(void); static void NORETURN canMonitorListen_process(void); @@ -144,6 +47,8 @@ static void NORETURN canMonitor_process(void) { //encoder_can_msg_t msg_enc; motor_can_msg_t msg_mot; odometry_can_msg_t msg_odo; + ghost_can_msg_t msg_ghost; + status_can_msg_t status_msg; can_tx_frame txm; robot_state_t odometry; Timer timer_can; @@ -154,7 +59,7 @@ static void NORETURN canMonitor_process(void) { txm.ide = 1; txm.sid = 0; - timer_setDelay(&timer_can, ms_to_ticks(10)); + timer_setDelay(&timer_can, ms_to_ticks(5)); timer_setEvent(&timer_can); while(1) { @@ -171,25 +76,7 @@ static void NORETURN canMonitor_process(void) { txm.eid = CAN_MSG_ENCODERS34; can_transmit(CAND1, &txm, ms_to_ticks(10));*/ - // Sending MOTOR3 data - msg_mot.data.position = mc_getPosition(MOTOR3); - msg_mot.data.speed = mc_getSpeed(MOTOR3); - - txm.data32[0] = msg_mot.data32[0]; - txm.data32[1] = msg_mot.data32[1]; - txm.eid = CAN_MSG_MOTOR3; - can_transmit(CAND1, &txm, ms_to_ticks(10)); - - // Sending MOTOR4 data - msg_mot.data.position = mc_getPosition(MOTOR4); - msg_mot.data.speed = mc_getSpeed(MOTOR4); - - txm.data32[0] = msg_mot.data32[0]; - txm.data32[1] = msg_mot.data32[1]; - txm.eid = CAN_MSG_MOTOR4; - can_transmit(CAND1, &txm, ms_to_ticks(10)); - - // Sending odometry data if not in HIL mode + // Sending odometry data if not in HIL mode or motor commands if in HIL mode if (mode != ROBOT_MODE_HIL) { odo_getState(&odometry); msg_odo.data.x = (int16_t)(odometry.x * 1000.0); @@ -205,8 +92,46 @@ static void NORETURN canMonitor_process(void) { txm.data32[1] = msg_odo.data32[1]; txm.eid = CAN_MSG_ODOMETRY; can_transmit(CAND1, &txm, ms_to_ticks(10)); + } else { + // Sending MOTOR3 data + msg_mot.data.position = mc_getPosition(MOTOR3); + msg_mot.data.speed = mc_getSpeed(MOTOR3); + + txm.data32[0] = msg_mot.data32[0]; + txm.data32[1] = msg_mot.data32[1]; + txm.eid = CAN_MSG_MOTOR3; + can_transmit(CAND1, &txm, ms_to_ticks(10)); + + // Sending MOTOR4 data + msg_mot.data.position = mc_getPosition(MOTOR4); + msg_mot.data.speed = mc_getSpeed(MOTOR4); + + txm.data32[0] = msg_mot.data32[0]; + txm.data32[1] = msg_mot.data32[1]; + txm.eid = CAN_MSG_MOTOR4; + can_transmit(CAND1, &txm, ms_to_ticks(10)); } + // Wait before sending the other packets + timer_waitEvent(&timer_can); + timer_add(&timer_can); + + // Sending ghost state + msg_ghost.data.state = dd_get_ghost_state(&odometry); + msg_ghost.data.x = (int16_t)(odometry.x * 1000.0); + msg_ghost.data.y = (int16_t)(odometry.y * 1000.0); + msg_ghost.data.theta = (int16_t)(odometry.theta * 1000.0); + txm.data32[0] = msg_ghost.data32[0]; + txm.data32[1] = msg_ghost.data32[1]; + txm.eid = CAN_MSG_GHOST; + can_transmit(CAND1, &txm, ms_to_ticks(10)); + + status_msg.data.is_moving = tc_is_working(MOTOR1 | MOTOR2 | MOTOR3 | MOTOR4); + txm.data32[0] = status_msg.data32[0]; + txm.data32[1] = status_msg.data32[1]; + txm.eid = CAN_MSG_STATUS; + can_transmit(CAND1, &txm, ms_to_ticks(10)); + // Wait for the next transmission timer timer_waitEvent(&timer_can); } @@ -219,12 +144,12 @@ static void NORETURN canMonitorListen_process(void) { can_tx_frame txm; robot_state_t odometry; - status_can_msg_t status_msg; move_can_msg_t move_msg; turn_can_msg_t turn_msg; odometry_can_msg_t odometry_msg; stop_can_msg_t stop_msg; controller_mode_can_msg_t controller_mode_msg; + bezier_can_msg_t bezier_msg; // Initialize constant parameters of TX frame txm.dlc = 8; @@ -238,12 +163,7 @@ static void NORETURN canMonitorListen_process(void) { if (frame.rtr == 1) { // Handle requests switch (frame.eid) { - case CAN_MSG_STATUS: - status_msg.data.is_moving = tc_is_working(MOTOR1 | MOTOR2 | MOTOR3 | MOTOR4); - txm.data32[0] = status_msg.data32[0]; - txm.data32[1] = status_msg.data32[1]; - txm.eid = CAN_MSG_STATUS; - can_transmit(CAND1, &txm, ms_to_ticks(10)); + default: break; } } else { @@ -261,6 +181,13 @@ static void NORETURN canMonitorListen_process(void) { if (!tc_is_working(TC_MASK(DD_LINEAR_SPEED_TC) | TC_MASK(DD_ROTATIONAL_SPEED_TC))) dd_turn(turn_msg.data.angle / 10000.0, turn_msg.data.speed / 1000.0, turn_msg.data.acceleration / 1000.0); break; + case CAN_MSG_BEZIER_ADD: + bezier_msg.data32[0] = frame.data32[0]; + bezier_msg.data32[1] = frame.data32[1]; + dd_add_bezier(bezier_msg.data.x_end/1000.0, bezier_msg.data.y_end/1000.0, + bezier_msg.data.d1/100.0, bezier_msg.data.d2/100.0, + bezier_msg.data.theta_end/1000.0, bezier_msg.data.v_end/1000.0); + break; case CAN_MSG_STOP: stop_msg.data32[0] = frame.data32[0]; stop_msg.data32[1] = frame.data32[1]; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.h index 2c83df0..da6ad7f 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/can_monitor.h @@ -18,6 +18,7 @@ #include "trajectory_controller.h" #include "odometry.h" #include "differential_drive.h" +#include "can_messages.h" void canMonitorInit(void); diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/controller_motor_stm32_user.mk b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/controller_motor_stm32_user.mk index 6f52c1d..bd55ecc 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/controller_motor_stm32_user.mk +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/controller_motor_stm32_user.mk @@ -17,6 +17,7 @@ controller_motor_stm32_USER_CSRC = \ $(controller_motor_stm32_SRC_PATH)/motor_controller.c \ $(controller_motor_stm32_SRC_PATH)/command_generator.c \ $(controller_motor_stm32_SRC_PATH)/trajectory_controller.c \ + $(controller_motor_stm32_SRC_PATH)/bezier_utils.c \ $(controller_motor_stm32_SRC_PATH)/differential_drive.c \ $(controller_motor_stm32_SRC_PATH)/can_monitor.c \ $(controller_motor_stm32_SRC_PATH)/main.c \ diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c index 85b643d..c22d8c8 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.c @@ -9,22 +9,188 @@ #include "differential_drive.h" +#ifndef MIN +#define MIN(a,b) ((a) < (b) ? (a) : (b)) +#endif + +PROC_DEFINE_STACK(stack_traj_following, KERN_MINSTACKSIZE * 32); + typedef struct { uint8_t initialized, enabled; - float wheel_radius, shaft_radius; + float params[2][4], dparams[2][4], ddparams[2][4]; + float du, v_tab[101]; + float goal[2], v_end, theta_end; + float start[2], theta_ini; +} dd_bezier_traj_t; + +typedef struct { + uint8_t initialized, enabled, running, working; + float wheel_radius, shaft_width; float last_lin_acceleration, last_rot_acceleration; + float v_max, at_max, ar_max; command_generator_t left_wheel_speed, right_wheel_speed; command_generator_t left_wheel, right_wheel; + uint8_t current_traj; + dd_bezier_traj_t trajs[2]; + float Ts, k1, k2, k3; + robot_state_t ghost_state; } dd_params_t; static dd_params_t params; -void dd_start(float wheel_radius, float shaft_width, float max_wheel_speed) { +static void NORETURN traj_following_process(void); + +static void NORETURN traj_following_process(void) { + Timer timer; + uint8_t next_traj, ui; + robot_state_t rs; + float cr, u, v_lin, v_ratio, v_max, v_rot, dxu, dyu; + float z1, z2, z3, w1, w2, u1, u2, dt; + dd_bezier_traj_t *traj; + int32_t last_time, cur_time; + + // configure timer + timer_setDelay(&timer, ms_to_ticks(params.Ts * 1000)); + timer_setEvent(&timer); + + // Indicate we are running + params.running = 1; + + // Init + params.working = 0; + next_traj = (params.current_traj + 1) % 2; + + while (1) { + if (params.enabled == 0) { + params.running = 0; + proc_exit(); + } else { + if (!params.working && params.trajs[next_traj].initialized) { + LED2_ON(); + params.working = 1; + u = 0; + ui = 0; + params.current_traj = next_traj; + traj = ¶ms.trajs[params.current_traj]; + next_traj = (params.current_traj + 1) % 2; + params.ghost_state.x = traj->start[0]; + params.ghost_state.y = traj->start[1]; + params.ghost_state.theta = traj->theta_ini; + traj->enabled = 1; + last_time = ticks_to_us(timer_clock()); + } + timer_add(&timer); + if (params.working) { + odo_getState(&rs); + + // Stop following the trajectory if we are close enough to our goal + if (u >= 1.0 || ((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { + //if (((rs.x-traj->goal[0]) * (rs.x-traj->goal[0]) + (rs.y-traj->goal[1]) * (rs.y-traj->goal[1])) <= (0.01*0.01)) { + LED2_OFF(); + params.working = 0; + traj->initialized = 0; + traj->enabled = 0; + if (!params.trajs[next_traj].initialized) { + // We have no other trajectory to follow, let's brake + dd_set_rotational_speed(0., params.at_max); + dd_set_linear_speed(0., params.at_max); + } + } else { + // We are following a trajectory, let's do it + // Compute ghost vehicule parameters + cr = bezier_cr(u, traj->dparams, traj->ddparams); + for (; ui*traj->du <= u; ui++); + if (ui*traj->du > 1.0) + ui--; + if (ui > 0) { + v_lin = traj->v_tab[ui-1] + + (traj->v_tab[ui]-traj->v_tab[ui-1]) * (u - traj->du*(ui-1))/traj->du; + } else { + v_lin = traj->v_tab[0]; + } + if (isnan(cr) || isinf(cr)) { + v_ratio = 1.0; + } else { + v_ratio = (cr + params.shaft_width/2.0) / (cr - params.shaft_width/2.0); + } + v_max = 2/(1+MIN(fabsf(v_ratio), fabsf(1.0/v_ratio)))*v_lin; + if (cr >= 0) { + v_rot = v_max * (1 - 1/v_ratio) / params.shaft_width; + } else { + v_rot = v_max * (v_ratio - 1) / params.shaft_width; + } + + // Evolution of the ghost vehicule state + cur_time = ticks_to_us(timer_clock()); + dt = (cur_time - last_time) * 1e-6; + dxu = bezier_apply(traj->dparams[0], u); + dyu = bezier_apply(traj->dparams[1], u); + u += v_lin/sqrtf(dxu*dxu+dyu*dyu)*dt; + //if (u >= 1.0) { + // u = 1.0; + //} else { + params.ghost_state.x += v_lin*cosf(params.ghost_state.theta)*dt; + params.ghost_state.y += v_lin*sinf(params.ghost_state.theta)*dt; + params.ghost_state.theta = fmodf(params.ghost_state.theta + v_rot*dt, 2*M_PI); + if (params.ghost_state.theta > M_PI) { + params.ghost_state.theta -= 2*M_PI; + } else if (params.ghost_state.theta <= M_PI) { + params.ghost_state.theta += 2*M_PI; + } + //} + + // Compute command + z1=(rs.x-params.ghost_state.x)*cosf(params.ghost_state.theta)+(rs.y-params.ghost_state.y)*sinf(params.ghost_state.theta); + z2=-(rs.x-params.ghost_state.x)*sinf(params.ghost_state.theta)+(rs.y-params.ghost_state.y)*cosf(params.ghost_state.theta); + z3=tanf(rs.theta-params.ghost_state.theta); + + w1=-params.k1*fabsf(v_lin)*(z1+z2*z3); + w2=-params.k2*v_lin*z2-params.k3*fabsf(v_lin)*z3; + + u1=(w1+v_lin)/cosf(rs.theta-params.ghost_state.theta); + 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.); + + // Keep current time + last_time = cur_time; + } + } + } + timer_waitEvent(&timer); // Wait for the remaining of the sample period + } +} + +void dd_start(float wheel_radius, float shaft_width, float max_wheel_speed, + float v_max, float at_max, float ar_max, + float k1, float k2, float k3, float Ts) { params.wheel_radius = wheel_radius; - params.shaft_radius = shaft_width; + params.shaft_width = shaft_width; params.last_lin_acceleration = 0.0; params.last_rot_acceleration = 0.0; + params.ghost_state.x = 0; + params.ghost_state.y = 0; + params.ghost_state.theta = 0; + + params.running = 0; + params.working = 0; + params.current_traj = 0; + params.trajs[0].initialized = 0; + params.trajs[1].initialized = 0; + params.trajs[0].enabled = 0; + params.trajs[1].enabled = 0; + params.v_max = v_max; + params.at_max = at_max; + params.ar_max = ar_max; + + params.k1 = k1; + params.k2 = k2; + params.k3 = k3; + params.Ts = Ts; + tc_new_controller(DD_LINEAR_SPEED_TC); tc_new_controller(DD_ROTATIONAL_SPEED_TC); new_dd_generator(¶ms.left_wheel_speed, @@ -51,6 +217,8 @@ void dd_start(float wheel_radius, float shaft_width, float max_wheel_speed) { params.initialized = 1; params.enabled = 1; + + proc_new(traj_following_process, NULL, sizeof(stack_traj_following), stack_traj_following); } void dd_pause(void) { @@ -104,15 +272,90 @@ void dd_turn(float angle, float speed, float acceleration) { void dd_set_linear_speed(float speed, float acceleration) { if (params.enabled) { - params.last_lin_acceleration = acceleration; - tc_goto_speed(DD_LINEAR_SPEED_TC, speed, params.last_lin_acceleration); + if (acceleration != 0.) { + params.last_lin_acceleration = acceleration; + tc_goto_speed(DD_LINEAR_SPEED_TC, speed, params.last_lin_acceleration); + } else { + tc_set_speed(DD_LINEAR_SPEED_TC, speed); + } } } void dd_set_rotational_speed(float speed, float acceleration) { if (params.enabled) { - params.last_rot_acceleration = acceleration; - tc_goto_speed(DD_ROTATIONAL_SPEED_TC, speed, params.last_rot_acceleration); + if (acceleration != 0.) { + params.last_rot_acceleration = acceleration; + tc_goto_speed(DD_ROTATIONAL_SPEED_TC, speed, params.last_rot_acceleration); + } else { + tc_set_speed(DD_ROTATIONAL_SPEED_TC, speed); + } } } +uint8_t dd_add_bezier(float x_end, float y_end, float d1, float d2, float end_angle, float end_speed) { + uint8_t t_ind; + robot_state_t rs; + dd_bezier_traj_t *traj; + float v_ini, x_ini, y_ini, theta_ini; + + t_ind = (params.current_traj + 1) % 2; + + if (params.trajs[t_ind].initialized == 1) { + return DD_TRAJECTORY_ALREADY_USED; + } else { + traj = ¶ms.trajs[t_ind]; + // New trajectory is not enabled + traj->enabled = 0; + + // Get starting parameters + if (params.trajs[params.current_traj].enabled) { + v_ini = params.trajs[params.current_traj].v_end; + x_ini = params.trajs[params.current_traj].goal[0]; + y_ini = params.trajs[params.current_traj].goal[1]; + theta_ini = params.trajs[params.current_traj].theta_end; + } else { + odo_getState(&rs); + x_ini = rs.x; + y_ini = rs.y; + theta_ini = rs.theta; + v_ini = 0.01; // non null low velocity to allow the system to start + } + + // Compute Bezier Spline parameters + bezier_generate(traj->params, + x_ini, y_ini, + x_ini + d1*cosf(theta_ini), y_ini + d1*sinf(theta_ini), + x_end - d2*cosf(end_angle), y_end - d2*sinf(end_angle), + x_end, y_end); + traj->goal[0] = x_end; + traj->goal[1] = y_end; + traj->v_end = end_speed; + traj->theta_end = end_angle; + traj->start[0] = x_ini; + traj->start[1] = y_ini; + traj->theta_ini = theta_ini; + // Differentiate parameters + bezier_diff(traj->params, traj->dparams); + bezier_diff(traj->dparams, traj->ddparams); + // Compute velocity profile + bezier_velocity_profile(traj->dparams, traj->ddparams, + params.v_max, params.at_max, params.ar_max, + v_ini, end_speed, + 0.01, traj->v_tab); + traj->du = 0.01; + + params.trajs[t_ind].initialized = 1; + return DD_NO_ERROR; + } +} + +uint8_t dd_get_ghost_state(robot_state_t *state) { + state->x = params.ghost_state.x; + state->y = params.ghost_state.y; + state->theta = params.ghost_state.theta; + + if (params.working == 1) + return DD_GHOST_MOVING; + else + return DD_GHOST_STOPPED; +} diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h index 61684ce..93fc4ef 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/differential_drive.h @@ -11,8 +11,11 @@ #define __DIFFERENTIAL_DRIVE_H #include <math.h> +#include <drv/timer.h> #include "trajectory_controller.h" #include "command_generator.h" +#include "odometry.h" +#include "bezier_utils.h" #ifndef DD_LINEAR_SPEED_TC #define DD_LINEAR_SPEED_TC 0 @@ -21,15 +24,28 @@ #define DD_ROTATIONAL_SPEED_TC 1 #endif +#define DD_NO_ERROR 0 +#define DD_TRAJECTORY_ALREADY_USED 1 + +#define DD_GHOST_STOPPED 0 +#define DD_GHOST_MOVING 1 + /* Initializes the differential drive * - wheel_radius : radius of the wheels (in meters) - * - shaft_width : propulsion shaft radius (in meters) - * - max_speed : maximum wheel speed (in rad/s) + * - shaft_width : propulsion shaft width (in meters) + * - max_wheel_speed : maximum wheel speed (in rad/s) + * - v_max : maximum linear speed (in m/s) + * - at_max : maximum tangential acceleration (in m/s/s) + * - ar_max : maximum radial acceleration (in m/s/s) + * - k1, k2, k3 : control loop gain for trajectory following + * - Ts : sample time for control loop in seconds * * Note : the differential drive system will use Trajectory controllers * DD_LINEAR_SPEED_TC and DD_ROTATIONAL_SPEED_TC */ -void dd_start(float wheel_radius, float shaft_width, float max_speed); +void dd_start(float wheel_radius, float shaft_width, float max_wheel_speed, + float v_max, float at_max, float ar_max, + float k1, float k2, float k3, float Ts); /* Pauses or Resumes the differential drive system. * In pause mode, the drive will accept no further command and actions will be @@ -74,4 +90,19 @@ void dd_turn(float angle, float speed, float acceleration); void dd_set_linear_speed(float speed, float acceleration); void dd_set_rotational_speed(float speed, float acceleration); +/* + * Add a Bezier Spline to the trajectory follower + */ +uint8_t dd_add_bezier(float x_end, float y_end, float d1, float d2, float end_angle, float end_speed); + +/* + * Return the current state of the followed ghost robot + * - state : pointer to a robot_state_t structure where the ghost state will be written + * + * return value : + * - DD_GHOST_MOVING : if a trajectory is currently followed + * - DD_GHOST_STOPPED : if the ghost robot is stopped + */ +uint8_t dd_get_ghost_state(robot_state_t *state); + #endif /* __DIFFERENTIAL_DRIVE_H */ diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c index 926c6ad..6b607e9 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/main.c @@ -47,7 +47,7 @@ static void init(void) // Start control of drive motors tc_init(); - dd_start(WHEEL_RADIUS, SHAFT_WIDTH, 4.8*2*M_PI); // limit wheel speed to 1.5 m/s + dd_start(WHEEL_RADIUS, SHAFT_WIDTH, 8*2*M_PI, 0.5, 1.0, 1.0, 0.7, 0.7, 1.0, 0.01); // Common parameters params.encoder_gain = -2.0*M_PI/2000.0/15.0; params.G0 = 0.0145; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.c b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.c index 5b01741..2ae2d4f 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.c +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.c @@ -299,6 +299,30 @@ void tc_goto_speed(uint8_t cntr_index, float speed, float acceleration) { cont->working = 1; } +void tc_set_speed(uint8_t cntr_index, float speed) { + trajectory_controller_t *cont; + + // Get the controller and verifies it is enabled + if (cntr_index >= NUM_TC_MAX) + return; + cont = &controllers[cntr_index]; + if (!cont->enabled) + return; + + // Disable a possibly running profile + cont->aut.state = TRAPEZOID_STATE_STOP; + remove_callback(&cont->position); + remove_callback(&cont->speed); + + // Set speed and acceleration + adjust_value(&cont->speed, speed); + adjust_speed(&cont->speed, 0.0); + + cont->working = 0; +} + + + void tc_move(tc_robot_t *robot, float distance, float speed, float acceleration) { float dis_s, spe_s, acc_s; diff --git a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.h b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.h index a4901a3..cf8452d 100644 --- a/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.h +++ b/elec/boards/Controller_Motor_STM32/Firmware/controller_motor_stm32/trajectory_controller.h @@ -76,6 +76,11 @@ void tc_goto(uint8_t cntr_index, float angle, float speed, float acceleration); */ void tc_goto_speed(uint8_t cntr_index, float speed, float acceleration); +/* + * Change the speed command of a controller without any concern about acceleration + */ +void tc_set_speed(uint8_t cntr_index, float speed); + /* Moves along a line * - robot : pointer to a structure describing the robot configuration * - distance : distance to move of (in meters), can be positive (forward) hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 19:05:31
|
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 4f1a9587a1dba18c3bd3e3b962dacaffab58c2db (commit) from af646d8661612a1b39fe7725d6b747fcec064ab0 (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 4f1a9587a1dba18c3bd3e3b962dacaffab58c2db Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 21:04:55 2011 +0200 [krobot_planner] change the motor moving condition ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_planner.ml b/info/control2011/src/tools/krobot_planner.ml index b591637..0dbe9f7 100644 --- a/info/control2011/src/tools/krobot_planner.ml +++ b/info/control2011/src/tools/krobot_planner.ml @@ -193,7 +193,7 @@ let go planner rotation_speed rotation_acceleration moving_speed moving_accelera 0.)) in - lwt () = Lwt_unix.sleep 2.0 in + lwt () = wait_done planner in (match planner.vertices with | _ :: l -> @@ -231,8 +231,10 @@ let handle_message planner (timestamp, message) = set_origin planner (planner.position, { vx = cos planner.orientation; vy = sin planner.orientation }) - | Motor_status(m1, m2, m3, m4) -> - planner.motors_moving <- m1 || m2 + + | Odometry_ghost(x, y, theta, following) -> + planner.motors_moving <- following + | _ -> () end hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 19:01:08
|
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 af646d8661612a1b39fe7725d6b747fcec064ab0 (commit) from 627cc580a2169b0b0cec5cb708e601410077633f (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 af646d8661612a1b39fe7725d6b747fcec064ab0 Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 21:00:01 2011 +0200 [krobot_viewer] cache motor statuses ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index 7e54aa5..a79ddea 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -55,6 +55,9 @@ type viewer = { mutable vertices : vertice list; (* The current trajectory. *) + + mutable motor_status : bool * bool * bool *bool; + (* Status of the four motor controller. *) } (* +-----------------------------------------------------------------+ @@ -345,24 +348,26 @@ let handle_message viewer (timestamp, message) = end | Motor_status(m1, m2, m3, m4) -> - let moving = m1 || m2 in - if moving then begin - viewer.statusbar_context#pop (); - let _ = viewer.statusbar_context#push - (if m1 then - "Moving..." - else - (if m2 then - "Turning..." - else - "") - ) in (); - end else - viewer.statusbar_context#pop (); - viewer.ui#entry_moving1#set_text (if m1 then "yes" else "no"); - viewer.ui#entry_moving2#set_text (if m2 then "yes" else "no"); - viewer.ui#entry_moving3#set_text (if m3 then "yes" else "no"); - viewer.ui#entry_moving4#set_text (if m4 then "yes" else "no") + if (m1, m2, m3, m4) <> viewer.motor_status then begin + viewer.motor_status <- (m1, m2, m3, m4); + if m1 || m2 then begin + viewer.statusbar_context#pop (); + let _ = viewer.statusbar_context#push + (if m1 then + "Moving..." + else + (if m2 then + "Turning..." + else + "") + ) in (); + end else + viewer.statusbar_context#pop (); + viewer.ui#entry_moving1#set_text (if m1 then "yes" else "no"); + viewer.ui#entry_moving2#set_text (if m2 then "yes" else "no"); + viewer.ui#entry_moving3#set_text (if m3 then "yes" else "no"); + viewer.ui#entry_moving4#set_text (if m4 then "yes" else "no") + end | Beacon_position(angle, distance, period) -> let newangle = math_mod_float (viewer.state.theta +. Krobot_config.rotary_beacon_index_pos +. angle) (2. *. pi) in @@ -466,6 +471,7 @@ lwt () = origin = ({ x = 0.; y = 0. }, { vx = 0.; vy = 0. }); vertices = []; statusbar_context = ui#statusbar#new_context ""; + motor_status = (false, false, false, false); } in (* Handle messages. *) hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 18:51:17
|
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 627cc580a2169b0b0cec5cb708e601410077633f (commit) from 8877ca0b604fe3db017076a12c87b2007e140d73 (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 627cc580a2169b0b0cec5cb708e601410077633f Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 20:50:20 2011 +0200 [krobot_viewer] do not send motor status request anymore ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_simulator.ml b/info/control2011/src/tools/krobot_simulator.ml index fa4f724..ad0bf78 100644 --- a/info/control2011/src/tools/krobot_simulator.ml +++ b/info/control2011/src/tools/krobot_simulator.ml @@ -241,6 +241,17 @@ lwt () = (* Sends the state of the robot. *) lwt () = Krobot_message.send bus (sim.time, Odometry(sim.state.x, sim.state.y, sim.state.theta)) in + (* Sends the state of the motors. *) + lwt () = + match sim.command with + | Turn(a, b) -> + Krobot_message.send bus (Unix.gettimeofday (), Motor_status(false, true, false, false)) + | Move(a, b) -> + Krobot_message.send bus (Unix.gettimeofday (), Motor_status(true, false, false, false)) + | _ -> + Krobot_message.send bus (Unix.gettimeofday (), Motor_status(false, false, false, false)) + in + lwt () = print sim in let (u1, u2) = velocities sim in diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index 3b30372..7e54aa5 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -568,11 +568,4 @@ lwt () = ); false)); - pick [ - waiter; - (* Sends motor status request continously. *) - while_lwt true do - lwt () = Krobot_message.send bus (Unix.gettimeofday (), Req_motor_status) in - Lwt_unix.sleep 0.2 - done; - ] + waiter hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 17:45:53
|
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 8877ca0b604fe3db017076a12c87b2007e140d73 (commit) from 5c74c5a3162edcc3b84f32a73124c853354287fd (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 8877ca0b604fe3db017076a12c87b2007e140d73 Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 19:45:25 2011 +0200 [info] add krobot-kill ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/_oasis b/info/control2011/_oasis index bf73cdb..e826386 100644 --- a/info/control2011/_oasis +++ b/info/control2011/_oasis @@ -149,6 +149,13 @@ Executable "krobot-planner" MainIs: krobot_planner.ml BuildDepends: krobot, lwt.syntax +Executable "krobot-kill" + Path: src/tools + Install: true + CompiledObject: best + MainIs: krobot_kill.ml + BuildDepends: krobot, lwt.syntax + # +-------------------------------------------------------------------+ # | Examples | # +-------------------------------------------------------------------+ diff --git a/info/control2011/_tags b/info/control2011/_tags index cadd635..0faf3ef 100644 --- a/info/control2011/_tags +++ b/info/control2011/_tags @@ -2,7 +2,7 @@ <src/interfaces/*.ml>: -syntax_camlp4o # OASIS_START -# DO NOT EDIT (digest: 1679d4e007e0054354522251924e527a) +# DO NOT EDIT (digest: c856ca92c511128600c4a9a2ddb551e7) # Library krobot "src/lib": include "src/lib/krobot.cmxs": use_krobot @@ -69,6 +69,11 @@ <examples/send_can.{native,byte}>: pkg_lwt.unix <examples/send_can.{native,byte}>: pkg_lwt.syntax <examples/send_can.{native,byte}>: pkg_lwt.react +# Executable krobot-kill +<src/tools/krobot_kill.{native,byte}>: use_krobot +<src/tools/krobot_kill.{native,byte}>: pkg_lwt.unix +<src/tools/krobot_kill.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_kill.{native,byte}>: pkg_lwt.react # Executable krobot-plot-battery <src/tools/krobot_plot_battery.{native,byte}>: use_krobot <src/tools/krobot_plot_battery.{native,byte}>: pkg_lwt.unix diff --git a/info/control2011/setup.ml b/info/control2011/setup.ml index 078b5ec..41e82e4 100644 --- a/info/control2011/setup.ml +++ b/info/control2011/setup.ml @@ -1,7 +1,7 @@ (* setup.ml generated for the first time by OASIS v0.2.0~alpha1 *) (* OASIS_START *) -(* DO NOT EDIT (digest: 30ea6aababbcb01f34ddeb36b478d1f7) *) +(* DO NOT EDIT (digest: d57b3cf1b9ea66ae670ea790a42da492) *) (* Regenerated by OASIS v0.2.0 Visit http://oasis.forge.ocamlcore.org for more information and @@ -5374,6 +5374,33 @@ let setup_t = bs_nativeopt = [(OASISExpr.EBool true, [])]; }, {exec_custom = false; exec_main_is = "send_can.ml"; }); + Executable + ({ + cs_name = "krobot-kill"; + cs_data = PropList.Data.create (); + cs_plugin_data = []; + }, + { + bs_build = [(OASISExpr.EBool true, true)]; + bs_install = [(OASISExpr.EBool true, true)]; + bs_path = "src/tools"; + bs_compiled_object = Best; + bs_build_depends = + [ + InternalLibrary "krobot"; + FindlibPackage ("lwt.syntax", None) + ]; + bs_build_tools = [ExternalTool "ocamlbuild"]; + bs_c_sources = []; + bs_data_files = []; + bs_ccopt = [(OASISExpr.EBool true, [])]; + bs_cclib = [(OASISExpr.EBool true, [])]; + bs_dlllib = [(OASISExpr.EBool true, [])]; + bs_dllpath = [(OASISExpr.EBool true, [])]; + bs_byteopt = [(OASISExpr.EBool true, [])]; + bs_nativeopt = [(OASISExpr.EBool true, [])]; + }, + {exec_custom = false; exec_main_is = "krobot_kill.ml"; }); Flag ({ cs_name = "gtk"; diff --git a/info/control2011/src/driver/krobot_driver.ml b/info/control2011/src/driver/krobot_driver.ml index 47004f1..9e5b578 100644 --- a/info/control2011/src/driver/krobot_driver.ml +++ b/info/control2011/src/driver/krobot_driver.ml @@ -18,12 +18,10 @@ open Krobot_bus +-----------------------------------------------------------------+ *) let fork = ref true -let kill = ref false let once = ref false let options = Arg.align [ "-no-fork", Arg.Clear fork, " Run in foreground"; - "-kill", Arg.Set kill, " Kill any running driver and exit"; "-once", Arg.Set once, " Do not reopen the device on errors"; ] diff --git a/info/control2011/src/tools/krobot_kill.ml b/info/control2011/src/tools/krobot_kill.ml new file mode 100644 index 0000000..77df879 --- /dev/null +++ b/info/control2011/src/tools/krobot_kill.ml @@ -0,0 +1,19 @@ +(* + * krobot_kill.ml + * -------------- + * Copyright : (c) 2011, Jeremie Dimino <je...@di...> + * Licence : BSD3 + * + * This file is a part of [kro]bot. + *) + +open Lwt +open Krobot_bus + +lwt () = + lwt bus = Krobot_bus.get () in + + join + (List.map + (fun prog -> Krobot_bus.send bus (Unix.gettimeofday (), Kill prog)) + (List.tl (Array.to_list Sys.argv))) hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 17:16:39
|
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 5c74c5a3162edcc3b84f32a73124c853354287fd (commit) from d68c3713a184beeec683548139d7af472a545b70 (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 5c74c5a3162edcc3b84f32a73124c853354287fd Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 19:16:06 2011 +0200 [krobot_viewer] fix rendering of the robot and the ghost ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index 43e01d8..3b30372 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -230,10 +230,10 @@ let draw viewer = Cairo.arc ctx 1.675 0.175 0.05 0. (2. *. pi); Cairo.fill ctx; - Cairo.save ctx; - List.iter (fun (state, alpha) -> + Cairo.save ctx; + (* Draw the robot *) Cairo.translate ctx state.pos.x state.pos.y; Cairo.rotate ctx state.theta; @@ -249,12 +249,12 @@ let draw viewer = Cairo.line_to ctx d (robot_size /. 4.); Cairo.line_to ctx (d +. robot_size /. 4.) 0.; Cairo.set_source_rgba ctx 0. 0. 0. 0.5; - Cairo.stroke ctx) + Cairo.stroke ctx; + + Cairo.restore ctx) [(viewer.ghost, 0.5); (viewer.state, 1.0)]; - Cairo.restore ctx; - (* Draw the beacon *) if viewer.beacon.valid then begin Cairo.arc ctx viewer.beacon.xbeacon viewer.beacon.ybeacon 0.04 0. (2. *. pi); hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 17:10:40
|
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 d68c3713a184beeec683548139d7af472a545b70 (commit) from 37baee2571d2c9ab630f4840cb3591934598d5fa (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 d68c3713a184beeec683548139d7af472a545b70 Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 19:09:57 2011 +0200 [krobot_viewer] show the ghost ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/lib/krobot_message.ml b/info/control2011/src/lib/krobot_message.ml index 62aff7a..94db4fc 100644 --- a/info/control2011/src/lib/krobot_message.ml +++ b/info/control2011/src/lib/krobot_message.ml @@ -32,6 +32,7 @@ type t = | Motor_bezier of float * float * float * float * float * float | Motor_stop | Odometry of float * float * float + | Odometry_ghost of float * float * float * bool | Set_odometry of float * float * float | Set_controller_mode of bool | Req_motor_status @@ -107,6 +108,10 @@ let to_string = function sprintf "Odometry(%f, %f, %f)" x y theta + | Odometry_ghost(x, y, theta, following) -> + sprintf + "Odometry_ghost(%f, %f, %f, %B)" + x y theta following | Set_odometry(x, y, theta) -> sprintf "Set_odometry(%f, %f, %f)" @@ -186,6 +191,18 @@ let encode = function ~remote:false ~format:F29bits ~data + | Odometry_ghost(x, y, theta, following) -> + let data = String.create 7 in + put_sint16 data 0 (truncate (x *. 1000.)); + put_sint16 data 2 (truncate (y *. 1000.)); + put_sint16 data 4 (truncate (theta *. 10000.)); + put_uint8 data 6 (if following then 1 else 0); + frame + ~identifier:105 + ~kind:Data + ~remote:false + ~format:F29bits + ~data | Motor_move(dist, speed, acc) -> let data = String.create 8 in put_sint32 data 0 (truncate (dist *. 1000.)); @@ -353,6 +370,12 @@ let decode frame = (float (get_sint16 frame.data 0) /. 1000., float (get_sint16 frame.data 2) /. 1000., float (get_sint16 frame.data 4) /. 10000.) + | 105 -> + Odometry_ghost + (float (get_sint16 frame.data 0) /. 1000., + float (get_sint16 frame.data 2) /. 1000., + float (get_sint16 frame.data 4) /. 10000., + get_uint8 frame.data 6 <> 0) | 201 -> Motor_move (float (get_sint32 frame.data 0) /. 1000., diff --git a/info/control2011/src/lib/krobot_message.mli b/info/control2011/src/lib/krobot_message.mli index 557994c..53df1d6 100644 --- a/info/control2011/src/lib/krobot_message.mli +++ b/info/control2011/src/lib/krobot_message.mli @@ -51,6 +51,9 @@ type t = | Odometry of float * float * float (** [Odometry(x, y, theta)] the position of the robot on the table. *) + | Odometry_ghost of float * float * float * bool + (** [Odometry_ghost(x, y, theta, following)]. [following] is + [true] iff the robot is following the ghost. *) | Set_odometry of float * float * float (** [set_odometry(x, y, theta)] sets the parameters of the odometry to the given ones. *) diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index 12926f4..43e01d8 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -44,6 +44,9 @@ type viewer = { mutable state : state; (* The state of the robot. *) + mutable ghost : state; + (* The state of the ghost. *) + mutable beacon : beacon; (* The state of the beacon. *) @@ -229,22 +232,26 @@ let draw viewer = Cairo.save ctx; - (* Draw the robot *) - Cairo.translate ctx viewer.state.pos.x viewer.state.pos.y; - Cairo.rotate ctx viewer.state.theta; - Cairo.rectangle ctx (-. wheels_position) (-. robot_size /. 2.) robot_size robot_size; - set_color ctx White; - Cairo.fill ctx; - - (* Draw an arrow on the robot *) - let d = robot_size /. 2. -. wheels_position in - Cairo.move_to ctx 0. 0.; - Cairo.line_to ctx (d +. robot_size /. 4.) 0.; - Cairo.line_to ctx d (-. robot_size /. 4.); - Cairo.line_to ctx d (robot_size /. 4.); - Cairo.line_to ctx (d +. robot_size /. 4.) 0.; - set_color ctx Black; - Cairo.stroke ctx; + List.iter + (fun (state, alpha) -> + (* Draw the robot *) + Cairo.translate ctx state.pos.x state.pos.y; + Cairo.rotate ctx state.theta; + Cairo.rectangle ctx (-. wheels_position) (-. robot_size /. 2.) robot_size robot_size; + Cairo.set_source_rgba ctx 1. 1. 1. alpha; + Cairo.fill ctx; + + (* Draw an arrow on the robot *) + let d = robot_size /. 2. -. wheels_position in + Cairo.move_to ctx 0. 0.; + Cairo.line_to ctx (d +. robot_size /. 4.) 0.; + Cairo.line_to ctx d (-. robot_size /. 4.); + Cairo.line_to ctx d (robot_size /. 4.); + Cairo.line_to ctx (d +. robot_size /. 4.) 0.; + Cairo.set_source_rgba ctx 0. 0. 0. 0.5; + Cairo.stroke ctx) + [(viewer.ghost, 0.5); + (viewer.state, 1.0)]; Cairo.restore ctx; @@ -328,6 +335,15 @@ let handle_message viewer (timestamp, message) = viewer.ui#entry_theta#set_text (string_of_float theta); queue_draw viewer end + + | Odometry_ghost(x, y, theta, following) -> + let angle = math_mod_float (theta) (2. *. pi) in + let ghost = { pos = { x; y }; theta = angle } in + if ghost <> viewer.ghost then begin + viewer.ghost <- ghost; + queue_draw viewer + end + | Motor_status(m1, m2, m3, m4) -> let moving = m1 || m2 in if moving then begin @@ -347,6 +363,7 @@ let handle_message viewer (timestamp, message) = viewer.ui#entry_moving2#set_text (if m2 then "yes" else "no"); viewer.ui#entry_moving3#set_text (if m3 then "yes" else "no"); viewer.ui#entry_moving4#set_text (if m4 then "yes" else "no") + | Beacon_position(angle, distance, period) -> let newangle = math_mod_float (viewer.state.theta +. Krobot_config.rotary_beacon_index_pos +. angle) (2. *. pi) in let x = viewer.state.pos.x +. distance *. cos (newangle) in @@ -361,11 +378,13 @@ let handle_message viewer (timestamp, message) = viewer.ui#beacon_period#set_text (string_of_float period); queue_draw viewer end + | Set_controller_mode hil -> if hil then viewer.ui#menu_mode_hil#set_active true else viewer.ui#menu_mode_normal#set_active true + | _ -> () end @@ -433,14 +452,16 @@ lwt () = ]; (* Create the viewer. *) + let init = { + pos = { x = 0.2; + y = 1.9 +. Krobot_config.robot_size /. 2. -. Krobot_config.wheels_position }; + theta = -0.5 *. pi + } in let viewer ={ bus; ui; - state = { - pos = { x = 0.2; - y = 1.9 +. Krobot_config.robot_size /. 2. -. Krobot_config.wheels_position }; - theta = -0.5 *. pi - }; + state = init; + ghost = init; beacon = { xbeacon = 1.; ybeacon = 1.; valid = false }; origin = ({ x = 0.; y = 0. }, { vx = 0.; vy = 0. }); vertices = []; hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 16:04:29
|
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 37baee2571d2c9ab630f4840cb3591934598d5fa (commit) from 4edca7b081fa144bd842ef7551e82e475957cd9b (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 37baee2571d2c9ab630f4840cb3591934598d5fa Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 18:03:50 2011 +0200 [info] remove files generated by ./configure (no longer used) ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/_oasis b/info/control2011/_oasis index 89543d8..bf73cdb 100644 --- a/info/control2011/_oasis +++ b/info/control2011/_oasis @@ -13,9 +13,6 @@ BuildTools: ocamlbuild Plugins: DevFiles (0.2), META (0.2) Synopsis: [Kro]bot Description: Control program for the Eurobot robotic cup. -FilesAB: - src/driver/bus.conf.ab, - src/services/fr.krobot.Service.Planner.service.ab # +-------------------------------------------------------------------+ # | Flags | diff --git a/info/control2011/setup.ml b/info/control2011/setup.ml index ecae0d6..078b5ec 100644 --- a/info/control2011/setup.ml +++ b/info/control2011/setup.ml @@ -1,7 +1,7 @@ (* setup.ml generated for the first time by OASIS v0.2.0~alpha1 *) (* OASIS_START *) -(* DO NOT EDIT (digest: 59697e01816cd0990967d00e7a4e65f9) *) +(* DO NOT EDIT (digest: 30ea6aababbcb01f34ddeb36b478d1f7) *) (* Regenerated by OASIS v0.2.0 Visit http://oasis.forge.ocamlcore.org for more information and @@ -5049,11 +5049,7 @@ let setup_t = pre_command = [(OASISExpr.EBool true, None)]; post_command = [(OASISExpr.EBool true, None)]; }; - files_ab = - [ - "src/driver/bus.conf.ab"; - "src/services/fr.krobot.Service.Planner.service.ab" - ]; + files_ab = []; sections = [ Library hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 15:47:34
|
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 4edca7b081fa144bd842ef7551e82e475957cd9b (commit) from 02784a1be45e3f59d96e5b550f94adb3e5034657 (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 4edca7b081fa144bd842ef7551e82e475957cd9b Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 17:46:14 2011 +0200 [krobot_hub] resolve host names instead of taking IP addresses ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_hub.ml b/info/control2011/src/tools/krobot_hub.ml index 360ea2a..406e505 100644 --- a/info/control2011/src/tools/krobot_hub.ml +++ b/info/control2011/src/tools/krobot_hub.ml @@ -72,10 +72,15 @@ let dispatch hub node = | Connection to another HUB | +-----------------------------------------------------------------+ *) -let link hub inet_addr = - let addr = Unix.ADDR_INET(inet_addr, port) in +let link hub host = while_lwt true do try_lwt + (* Resolve the host. *) + lwt entry = Lwt_unix.gethostbyname host in + + (* Create the address of the host. *) + let addr = Unix.ADDR_INET(entry.Unix.h_addr_list.(0), port) in + (* Try to connect to the remote HUB. *) lwt channels = Lwt_io.open_connection addr in @@ -85,7 +90,7 @@ let link hub inet_addr = (* Dispatch until error. *) dispatch hub node with exn -> - ignore (Lwt_log.error_f ~section ~exn "cannot connect to '%s'" (Unix.string_of_inet_addr inet_addr)); + ignore (Lwt_log.error_f ~section ~exn "cannot connect to '%s'" host); (* Wait a bit before retrying. *) Lwt_unix.sleep 1.0 @@ -116,20 +121,14 @@ let usage = "\ Usage: krobot-hub [options] [addresses] options are:" -let addresses = ref [] - -let parse_address addr = - try - addresses := Unix.inet_addr_of_string addr :: !addresses - with Failure _ -> - raise (Arg.Bad(Printf.sprintf "invalid inet address '%s'" addr)) +let hosts = ref [] (* +-----------------------------------------------------------------+ | Entry point | +-----------------------------------------------------------------+ *) lwt () = - Arg.parse options parse_address usage; + Arg.parse options (fun host -> hosts := host :: !hosts) usage; (* Create the local HUB. *) let hub = { connections = Lwt_sequence.create () } in @@ -138,7 +137,7 @@ lwt () = ignore (Lwt_io.establish_server (Unix.ADDR_INET(Unix.inet_addr_any, port)) (fun channels -> handle_connection hub channels)); (* Launch link to other HUBs. *) - List.iter (fun addr -> ignore (link hub addr)) !addresses; + List.iter (fun host -> ignore (link hub host)) !hosts; (* Fork if not prevented. *) if !fork then Lwt_daemon.daemonize (); hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 12:36:50
|
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 02784a1be45e3f59d96e5b550f94adb3e5034657 (commit) from 3f167129823c37347beb03b6774740ae5b7689c2 (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 02784a1be45e3f59d96e5b550f94adb3e5034657 Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 14:36:17 2011 +0200 [krobot_viewer] emit a Send message at startup ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/tools/krobot_viewer.ml b/info/control2011/src/tools/krobot_viewer.ml index 692bdcd..12926f4 100644 --- a/info/control2011/src/tools/krobot_viewer.ml +++ b/info/control2011/src/tools/krobot_viewer.ml @@ -450,6 +450,9 @@ lwt () = (* Handle messages. *) E.keep (E.map (fun msg -> handle_message viewer msg) (Krobot_bus.recv bus)); + (* Ask for initial parameters. *) + lwt () = Krobot_bus.send bus (Unix.gettimeofday (), Send) in + (* Adjusts The position of paned. *) viewer.ui#scene_paned#set_position ((viewer.ui#window#default_width * 5) / 8); hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-19 12:27:07
|
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 3f167129823c37347beb03b6774740ae5b7689c2 (commit) from 3c5104a9beb21ba05f513b15c7798075364ca875 (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 3f167129823c37347beb03b6774740ae5b7689c2 Author: Jérémie Dimino <je...@di...> Date: Tue Apr 19 14:25:03 2011 +0200 [info] drop D-Bus in flavor of a simple home made network protocol ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/_oasis b/info/control2011/_oasis index c14f942..89543d8 100644 --- a/info/control2011/_oasis +++ b/info/control2011/_oasis @@ -31,18 +31,17 @@ Flag gtk Library krobot FindlibName: krobot - BuildDepends: lwt.unix, lwt.syntax, obus, krobot.interfaces + BuildDepends: lwt.unix, lwt.syntax, lwt.react XMETADescription: The [Kro]bot library - XMETARequires: lwt.unix, obus, krobot.interfaces + XMETARequires: lwt.unix, lwt.react Path: src/lib Install: true Modules: Krobot_can, Krobot_bus, Krobot_message, - Krobot_service, Krobot_geom, - Krobot_planner + Krobot_config CSources: krobot_message_stubs.c @@ -57,19 +56,6 @@ Library "krobot-can" Modules: Krobot_can_bus CSources: can_stubs.c -Library "krobot-interfaces" - FindlibName: interfaces - FindlibParent: krobot - BuildDepends: obus - XMETADescription: [Kro]bot D-Bus interfaces - XMETARequires: obus - Path: src/interfaces - Install: true - Modules: - Krobot_interface_can, - Krobot_interface_service, - Krobot_interface_planner - # +-------------------------------------------------------------------+ # | The driver | # +-------------------------------------------------------------------+ @@ -80,12 +66,18 @@ Executable "krobot-driver" CompiledObject: best MainIs: krobot_driver.ml BuildDepends: krobot.can, lwt.syntax - DataFiles: bus.conf # +-------------------------------------------------------------------+ # | Tools | # +-------------------------------------------------------------------+ +Executable "krobot-hub" + Path: src/tools + Install: true + CompiledObject: best + MainIs: krobot_hub.ml + BuildDepends: lwt.unix, lwt.syntax + Executable "krobot-dump" Path: src/tools Install: true @@ -102,7 +94,8 @@ Executable "krobot-dump-encoders" Executable "krobot-record" Path: src/tools - Install: true + Install: false + Build: false CompiledObject: best MainIs: krobot_record.ml BuildDepends: krobot, lwt.syntax @@ -114,20 +107,6 @@ Executable "krobot-replay" MainIs: krobot_replay.ml BuildDepends: krobot, lwt.syntax -Executable "krobot-remote" - Path: src/tools - Install: true - CompiledObject: best - MainIs: krobot_remote.ml - BuildDepends: krobot, lwt.syntax - -Executable "krobot-local" - Path: src/tools - Install: true - CompiledObject: best - MainIs: krobot_local.ml - BuildDepends: krobot, lwt.syntax - Executable "krobot-plot" Path: src/tools Build$: flag(gtk) @@ -166,17 +145,12 @@ Executable "krobot-hil-simulator" MainIs: krobot_hil_simulator.ml BuildDepends: krobot, lwt.syntax -# +-------------------------------------------------------------------+ -# | Services | -# +-------------------------------------------------------------------+ - -Executable "krobot-service-planner" - Path: src/services +Executable "krobot-planner" + Path: src/tools Install: true CompiledObject: best - MainIs: krobot_service_planner.ml + MainIs: krobot_planner.ml BuildDepends: krobot, lwt.syntax - DataFiles: fr.krobot.Service.Planner.service ($datadir/$pkg_name/services) # +-------------------------------------------------------------------+ # | Examples | diff --git a/info/control2011/_tags b/info/control2011/_tags index 650cedb..cadd635 100644 --- a/info/control2011/_tags +++ b/info/control2011/_tags @@ -2,160 +2,122 @@ <src/interfaces/*.ml>: -syntax_camlp4o # OASIS_START -# DO NOT EDIT (digest: 28c051595fc8936deb8eca602b892268) -# Library krobot-interfaces -"src/interfaces": include -"src/interfaces/krobot-interfaces.cmxs": use_krobot-interfaces -<src/interfaces/*.ml{,i}>: pkg_obus +# DO NOT EDIT (digest: 1679d4e007e0054354522251924e527a) # Library krobot "src/lib": include "src/lib/krobot.cmxs": use_krobot <src/lib/krobot.{cma,cmxa}>: use_libkrobot -<src/lib/*.ml{,i}>: use_krobot-interfaces -<src/lib/*.ml{,i}>: pkg_obus <src/lib/*.ml{,i}>: pkg_lwt.unix <src/lib/*.ml{,i}>: pkg_lwt.syntax -"src/lib/krobot_message_stubs.c": use_krobot-interfaces -"src/lib/krobot_message_stubs.c": pkg_obus +<src/lib/*.ml{,i}>: pkg_lwt.react "src/lib/krobot_message_stubs.c": pkg_lwt.unix "src/lib/krobot_message_stubs.c": pkg_lwt.syntax +"src/lib/krobot_message_stubs.c": pkg_lwt.react # Library krobot-can "src/can": include "src/can/krobot-can.cmxs": use_krobot-can <src/can/krobot-can.{cma,cmxa}>: use_libkrobot-can <src/can/*.ml{,i}>: use_krobot -<src/can/*.ml{,i}>: use_krobot-interfaces -<src/can/*.ml{,i}>: pkg_obus <src/can/*.ml{,i}>: pkg_lwt.unix <src/can/*.ml{,i}>: pkg_lwt.syntax +<src/can/*.ml{,i}>: pkg_lwt.react "src/can/can_stubs.c": use_krobot -"src/can/can_stubs.c": use_krobot-interfaces -"src/can/can_stubs.c": pkg_obus "src/can/can_stubs.c": pkg_lwt.unix "src/can/can_stubs.c": pkg_lwt.syntax +"src/can/can_stubs.c": pkg_lwt.react # Executable krobot-dump <src/tools/krobot_dump.{native,byte}>: use_krobot -<src/tools/krobot_dump.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_dump.{native,byte}>: pkg_obus <src/tools/krobot_dump.{native,byte}>: pkg_lwt.unix <src/tools/krobot_dump.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_dump.{native,byte}>: pkg_lwt.react # Executable krobot-dump-encoders <src/tools/krobot_dump_encoders.{native,byte}>: use_krobot -<src/tools/krobot_dump_encoders.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_dump_encoders.{native,byte}>: pkg_obus <src/tools/krobot_dump_encoders.{native,byte}>: pkg_lwt.unix <src/tools/krobot_dump_encoders.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_dump_encoders.{native,byte}>: pkg_lwt.react # Executable krobot-driver <src/driver/krobot_driver.{native,byte}>: use_krobot-can <src/driver/krobot_driver.{native,byte}>: use_krobot -<src/driver/krobot_driver.{native,byte}>: use_krobot-interfaces -<src/driver/krobot_driver.{native,byte}>: pkg_obus <src/driver/krobot_driver.{native,byte}>: pkg_lwt.unix <src/driver/krobot_driver.{native,byte}>: pkg_lwt.syntax +<src/driver/krobot_driver.{native,byte}>: pkg_lwt.react <src/driver/*.ml{,i}>: use_krobot-can <src/driver/*.ml{,i}>: use_krobot -<src/driver/*.ml{,i}>: use_krobot-interfaces -<src/driver/*.ml{,i}>: pkg_obus <src/driver/*.ml{,i}>: pkg_lwt.unix <src/driver/*.ml{,i}>: pkg_lwt.syntax +<src/driver/*.ml{,i}>: pkg_lwt.react # Executable krobot-viewer <src/tools/krobot_viewer.{native,byte}>: use_krobot -<src/tools/krobot_viewer.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_viewer.{native,byte}>: pkg_obus <src/tools/krobot_viewer.{native,byte}>: pkg_lwt.unix <src/tools/krobot_viewer.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_viewer.{native,byte}>: pkg_lwt.react <src/tools/krobot_viewer.{native,byte}>: pkg_lwt.glib <src/tools/krobot_viewer.{native,byte}>: pkg_lablgtk2.glade <src/tools/krobot_viewer.{native,byte}>: pkg_cairo.lablgtk2 <src/tools/*.ml{,i}>: pkg_lablgtk2.glade # Executable krobot-hil-simulator <src/tools/krobot_hil_simulator.{native,byte}>: use_krobot -<src/tools/krobot_hil_simulator.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_hil_simulator.{native,byte}>: pkg_obus <src/tools/krobot_hil_simulator.{native,byte}>: pkg_lwt.unix <src/tools/krobot_hil_simulator.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_hil_simulator.{native,byte}>: pkg_lwt.react +# Executable krobot-hub +<src/tools/krobot_hub.{native,byte}>: pkg_lwt.unix +<src/tools/krobot_hub.{native,byte}>: pkg_lwt.syntax # Executable send-can <examples/send_can.{native,byte}>: use_krobot-can <examples/send_can.{native,byte}>: use_krobot -<examples/send_can.{native,byte}>: use_krobot-interfaces -<examples/send_can.{native,byte}>: pkg_obus <examples/send_can.{native,byte}>: pkg_lwt.unix <examples/send_can.{native,byte}>: pkg_lwt.syntax +<examples/send_can.{native,byte}>: pkg_lwt.react # Executable krobot-plot-battery <src/tools/krobot_plot_battery.{native,byte}>: use_krobot -<src/tools/krobot_plot_battery.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_plot_battery.{native,byte}>: pkg_obus <src/tools/krobot_plot_battery.{native,byte}>: pkg_lwt.unix <src/tools/krobot_plot_battery.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_plot_battery.{native,byte}>: pkg_lwt.react <src/tools/krobot_plot_battery.{native,byte}>: pkg_lwt.glib <src/tools/krobot_plot_battery.{native,byte}>: pkg_cairo.lablgtk2 -# Executable krobot-service-planner -<src/services/krobot_service_planner.{native,byte}>: use_krobot -<src/services/krobot_service_planner.{native,byte}>: use_krobot-interfaces -<src/services/krobot_service_planner.{native,byte}>: pkg_obus -<src/services/krobot_service_planner.{native,byte}>: pkg_lwt.unix -<src/services/krobot_service_planner.{native,byte}>: pkg_lwt.syntax -<src/services/*.ml{,i}>: use_krobot -<src/services/*.ml{,i}>: use_krobot-interfaces -<src/services/*.ml{,i}>: pkg_obus -<src/services/*.ml{,i}>: pkg_lwt.unix -<src/services/*.ml{,i}>: pkg_lwt.syntax -# Executable krobot-remote -<src/tools/krobot_remote.{native,byte}>: use_krobot -<src/tools/krobot_remote.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_remote.{native,byte}>: pkg_obus -<src/tools/krobot_remote.{native,byte}>: pkg_lwt.unix -<src/tools/krobot_remote.{native,byte}>: pkg_lwt.syntax # Executable krobot-replay <src/tools/krobot_replay.{native,byte}>: use_krobot -<src/tools/krobot_replay.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_replay.{native,byte}>: pkg_obus <src/tools/krobot_replay.{native,byte}>: pkg_lwt.unix <src/tools/krobot_replay.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_replay.{native,byte}>: pkg_lwt.react # Executable dump-can <examples/dump_can.{native,byte}>: use_krobot-can <examples/dump_can.{native,byte}>: use_krobot -<examples/dump_can.{native,byte}>: use_krobot-interfaces -<examples/dump_can.{native,byte}>: pkg_obus <examples/dump_can.{native,byte}>: pkg_lwt.unix <examples/dump_can.{native,byte}>: pkg_lwt.syntax +<examples/dump_can.{native,byte}>: pkg_lwt.react <examples/*.ml{,i}>: use_krobot-can <examples/*.ml{,i}>: use_krobot -<examples/*.ml{,i}>: use_krobot-interfaces -<examples/*.ml{,i}>: pkg_obus <examples/*.ml{,i}>: pkg_lwt.unix <examples/*.ml{,i}>: pkg_lwt.syntax -# Executable krobot-local -<src/tools/krobot_local.{native,byte}>: use_krobot -<src/tools/krobot_local.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_local.{native,byte}>: pkg_obus -<src/tools/krobot_local.{native,byte}>: pkg_lwt.unix -<src/tools/krobot_local.{native,byte}>: pkg_lwt.syntax +<examples/*.ml{,i}>: pkg_lwt.react +# Executable krobot-planner +<src/tools/krobot_planner.{native,byte}>: use_krobot +<src/tools/krobot_planner.{native,byte}>: pkg_lwt.unix +<src/tools/krobot_planner.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_planner.{native,byte}>: pkg_lwt.react # Executable krobot-record <src/tools/krobot_record.{native,byte}>: use_krobot -<src/tools/krobot_record.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_record.{native,byte}>: pkg_obus <src/tools/krobot_record.{native,byte}>: pkg_lwt.unix <src/tools/krobot_record.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_record.{native,byte}>: pkg_lwt.react # Executable krobot-plot <src/tools/krobot_plot.{native,byte}>: use_krobot -<src/tools/krobot_plot.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_plot.{native,byte}>: pkg_obus <src/tools/krobot_plot.{native,byte}>: pkg_lwt.unix <src/tools/krobot_plot.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_plot.{native,byte}>: pkg_lwt.react <src/tools/krobot_plot.{native,byte}>: pkg_lwt.glib <src/tools/krobot_plot.{native,byte}>: pkg_cairo.lablgtk2 <src/tools/*.ml{,i}>: pkg_lwt.glib <src/tools/*.ml{,i}>: pkg_cairo.lablgtk2 # Executable krobot-simulator <src/tools/krobot_simulator.{native,byte}>: use_krobot -<src/tools/krobot_simulator.{native,byte}>: use_krobot-interfaces -<src/tools/krobot_simulator.{native,byte}>: pkg_obus <src/tools/krobot_simulator.{native,byte}>: pkg_lwt.unix <src/tools/krobot_simulator.{native,byte}>: pkg_lwt.syntax +<src/tools/krobot_simulator.{native,byte}>: pkg_lwt.react <src/tools/*.ml{,i}>: use_krobot -<src/tools/*.ml{,i}>: use_krobot-interfaces -<src/tools/*.ml{,i}>: pkg_obus <src/tools/*.ml{,i}>: pkg_lwt.unix <src/tools/*.ml{,i}>: pkg_lwt.syntax +<src/tools/*.ml{,i}>: pkg_lwt.react # OASIS_STOP diff --git a/info/control2011/krobot-api.odocl b/info/control2011/krobot-api.odocl index c450da7..1e10a3e 100644 --- a/info/control2011/krobot-api.odocl +++ b/info/control2011/krobot-api.odocl @@ -1,10 +1,9 @@ # OASIS_START -# DO NOT EDIT (digest: 38c17322394dfbb39f5f25c95efe932e) +# DO NOT EDIT (digest: 802a60f0417652c8e0b1a85294fd57f0) src/lib/Krobot_can src/lib/Krobot_bus src/lib/Krobot_message -src/lib/Krobot_service src/lib/Krobot_geom -src/lib/Krobot_planner +src/lib/Krobot_config src/can/Krobot_can_bus # OASIS_STOP diff --git a/info/control2011/myocamlbuild.ml b/info/control2011/myocamlbuild.ml index 20d8e84..73d0550 100644 --- a/info/control2011/myocamlbuild.ml +++ b/info/control2011/myocamlbuild.ml @@ -1,5 +1,5 @@ (* OASIS_START *) -(* DO NOT EDIT (digest: 1ca7268f789f49955feedef89f6b4ca9) *) +(* DO NOT EDIT (digest: 6313720c4a9fa3712417ffee35de107d) *) module OASISGettext = struct # 21 "/home/dim/sources/oasis/src/oasis/OASISGettext.ml" @@ -452,11 +452,7 @@ open Ocamlbuild_plugin;; let package_default = { MyOCamlbuildBase.lib_ocaml = - [ - ("src/interfaces/krobot-interfaces", ["src/interfaces"]); - ("src/lib/krobot", ["src/lib"]); - ("src/can/krobot-can", ["src/can"]) - ]; + [("src/lib/krobot", ["src/lib"]); ("src/can/krobot-can", ["src/can"])]; lib_c = [("krobot", "src/lib", []); ("krobot-can", "src/can", [])]; flags = []; } diff --git a/info/control2011/setup.ml b/info/control2011/setup.ml index 5b8befa..ecae0d6 100644 --- a/info/control2011/setup.ml +++ b/info/control2011/setup.ml @@ -1,7 +1,7 @@ (* setup.ml generated for the first time by OASIS v0.2.0~alpha1 *) (* OASIS_START *) -(* DO NOT EDIT (digest: b04695e11f7527ee760b637f6ae5beb4) *) +(* DO NOT EDIT (digest: 59697e01816cd0990967d00e7a4e65f9) *) (* Regenerated by OASIS v0.2.0 Visit http://oasis.forge.ocamlcore.org for more information and @@ -5058,40 +5058,6 @@ let setup_t = [ Library ({ - cs_name = "krobot-interfaces"; - cs_data = PropList.Data.create (); - cs_plugin_data = []; - }, - { - bs_build = [(OASISExpr.EBool true, true)]; - bs_install = [(OASISExpr.EBool true, true)]; - bs_path = "src/interfaces"; - bs_compiled_object = Best; - bs_build_depends = [FindlibPackage ("obus", None)]; - bs_build_tools = [ExternalTool "ocamlbuild"]; - bs_c_sources = []; - bs_data_files = []; - bs_ccopt = [(OASISExpr.EBool true, [])]; - bs_cclib = [(OASISExpr.EBool true, [])]; - bs_dlllib = [(OASISExpr.EBool true, [])]; - bs_dllpath = [(OASISExpr.EBool true, [])]; - bs_byteopt = [(OASISExpr.EBool true, [])]; - bs_nativeopt = [(OASISExpr.EBool true, [])]; - }, - { - lib_modules = - [ - "Krobot_interface_can"; - "Krobot_interface_service"; - "Krobot_interface_planner" - ]; - lib_internal_modules = []; - lib_findlib_parent = Some "krobot"; - lib_findlib_name = Some "interfaces"; - lib_findlib_containers = []; - }); - Library - ({ cs_name = "krobot"; cs_data = PropList.Data.create (); cs_plugin_data = []; @@ -5105,8 +5071,7 @@ let setup_t = [ FindlibPackage ("lwt.unix", None); FindlibPackage ("lwt.syntax", None); - FindlibPackage ("obus", None); - InternalLibrary "krobot-interfaces" + FindlibPackage ("lwt.react", None) ]; bs_build_tools = [ExternalTool "ocamlbuild"]; bs_c_sources = ["krobot_message_stubs.c"]; @@ -5124,9 +5089,8 @@ let setup_t = "Krobot_can"; "Krobot_bus"; "Krobot_message"; - "Krobot_service"; "Krobot_geom"; - "Krobot_planner" + "Krobot_config" ]; lib_internal_modules = []; lib_findlib_parent = None; @@ -5283,7 +5247,7 @@ let setup_t = ]; bs_build_tools = [ExternalTool "ocamlbuild"]; bs_c_sources = []; - bs_data_files = [("bus.conf", None)]; + bs_data_files = []; bs_ccopt = [(OASISExpr.EBool true, [])]; bs_cclib = [(OASISExpr.EBool true, [])]; bs_dlllib = [(OASISExpr.EBool true, [])]; @@ -5362,6 +5326,33 @@ let setup_t = }); Executable ({ + cs_name = "krobot-hub"; + cs_data = PropList.Data.create (); + cs_plugin_data = []; + }, + { + bs_build = [(OASISExpr.EBool true, true)]; + bs_install = [(OASISExpr.EBool true, true)]; + bs_path = "src/tools"; + bs_compiled_object = Best; + bs_build_depends = + [ + FindlibPackage ("lwt.unix", None); + FindlibPackage ("lwt.syntax", None) + ]; + bs_build_tools = [ExternalTool "ocamlbuild"]; + bs_c_sources = []; + bs_data_files = []; + bs_ccopt = [(OASISExpr.EBool true, [])]; + bs_cclib = [(OASISExpr.EBool true, [])]; + bs_dlllib = [(OASISExpr.EBool true, [])]; + bs_dllpath = [(OASISExpr.EBool true, [])]; + bs_byteopt = [(OASISExpr.EBool true, [])]; + bs_nativeopt = [(OASISExpr.EBool true, [])]; + }, + {exec_custom = false; exec_main_is = "krobot_hub.ml"; }); + Executable + ({ cs_name = "send-can"; cs_data = PropList.Data.create (); cs_plugin_data = []; @@ -5439,67 +5430,6 @@ let setup_t = }); Executable ({ - cs_name = "krobot-service-planner"; - cs_data = PropList.Data.create (); - cs_plugin_data = []; - }, - { - bs_build = [(OASISExpr.EBool true, true)]; - bs_install = [(OASISExpr.EBool true, true)]; - bs_path = "src/services"; - bs_compiled_object = Best; - bs_build_depends = - [ - InternalLibrary "krobot"; - FindlibPackage ("lwt.syntax", None) - ]; - bs_build_tools = [ExternalTool "ocamlbuild"]; - bs_c_sources = []; - bs_data_files = - [ - ("fr.krobot.Service.Planner.service", - Some "$datadir/$pkg_name/services") - ]; - bs_ccopt = [(OASISExpr.EBool true, [])]; - bs_cclib = [(OASISExpr.EBool true, [])]; - bs_dlllib = [(OASISExpr.EBool true, [])]; - bs_dllpath = [(OASISExpr.EBool true, [])]; - bs_byteopt = [(OASISExpr.EBool true, [])]; - bs_nativeopt = [(OASISExpr.EBool true, [])]; - }, - { - exec_custom = false; - exec_main_is = "krobot_service_planner.ml"; - }); - Executable - ({ - cs_name = "krobot-remote"; - cs_data = PropList.Data.create (); - cs_plugin_data = []; - }, - { - bs_build = [(OASISExpr.EBool true, true)]; - bs_install = [(OASISExpr.EBool true, true)]; - bs_path = "src/tools"; - bs_compiled_object = Best; - bs_build_depends = - [ - InternalLibrary "krobot"; - FindlibPackage ("lwt.syntax", None) - ]; - bs_build_tools = [ExternalTool "ocamlbuild"]; - bs_c_sources = []; - bs_data_files = []; - bs_ccopt = [(OASISExpr.EBool true, [])]; - bs_cclib = [(OASISExpr.EBool true, [])]; - bs_dlllib = [(OASISExpr.EBool true, [])]; - bs_dllpath = [(OASISExpr.EBool true, [])]; - bs_byteopt = [(OASISExpr.EBool true, [])]; - bs_nativeopt = [(OASISExpr.EBool true, [])]; - }, - {exec_custom = false; exec_main_is = "krobot_remote.ml"; }); - Executable - ({ cs_name = "krobot-replay"; cs_data = PropList.Data.create (); cs_plugin_data = []; @@ -5554,7 +5484,7 @@ let setup_t = {exec_custom = false; exec_main_is = "dump_can.ml"; }); Executable ({ - cs_name = "krobot-local"; + cs_name = "krobot-planner"; cs_data = PropList.Data.create (); cs_plugin_data = []; }, @@ -5578,7 +5508,8 @@ let setup_t = bs_byteopt = [(OASISExpr.EBool true, [])]; bs_nativeopt = [(OASISExpr.EBool true, [])]; }, - {exec_custom = false; exec_main_is = "krobot_local.ml"; }); + {exec_custom = false; exec_main_is = "krobot_planner.ml"; + }); Executable ({ cs_name = "krobot-record"; @@ -5586,8 +5517,8 @@ let setup_t = cs_plugin_data = []; }, { - bs_build = [(OASISExpr.EBool true, true)]; - bs_install = [(OASISExpr.EBool true, true)]; + bs_build = [(OASISExpr.EBool true, false)]; + bs_install = [(OASISExpr.EBool true, false)]; bs_path = "src/tools"; bs_compiled_object = Best; bs_build_depends = diff --git a/info/control2011/src/driver/bus.conf.ab b/info/control2011/src/driver/bus.conf.ab deleted file mode 100644 index ae988d4..0000000 --- a/info/control2011/src/driver/bus.conf.ab +++ /dev/null @@ -1,34 +0,0 @@ -<!-- Configuration of the D-Bus daemon used by programs of the robot --> - -<!DOCTYPE busconfig PUBLIC "-//freedesktop//DTD D-Bus Bus Krobot_configuration 1.0//EN" - "http://www.freedesktop.org/standards/dbus/1.0/busconfig.dtd"> -<busconfig> - <keep_umask/> - - <!-- Krobot D-Bus daemon default address --> - <listen>unix:abstract=krobot</listen> - - <!-- Directory for .service files --> - <servicedir>$(datadir)/krobot/services</servicedir> - - <!-- Allow everything --> - <policy context="default"> - <allow send_destination="*" eavesdrop="true"/> - <allow eavesdrop="true"/> - <allow own="*"/> - </policy> - - <!-- Raise limits --> - <limit name="max_incoming_bytes">1000000000</limit> - <limit name="max_outgoing_bytes">1000000000</limit> - <limit name="max_message_size">1000000000</limit> - <limit name="service_start_timeout">120000</limit> - <limit name="auth_timeout">240000</limit> - <limit name="max_completed_connections">100000</limit> - <limit name="max_incomplete_connections">10000</limit> - <limit name="max_connections_per_user">100000</limit> - <limit name="max_pending_service_starts">10000</limit> - <limit name="max_names_per_connection">50000</limit> - <limit name="max_match_rules_per_connection">50000</limit> - <limit name="max_replies_per_connection">50000</limit> -</busconfig> diff --git a/info/control2011/src/driver/krobot_driver.ml b/info/control2011/src/driver/krobot_driver.ml index 2d6141a..47004f1 100644 --- a/info/control2011/src/driver/krobot_driver.ml +++ b/info/control2011/src/driver/krobot_driver.ml @@ -11,6 +11,7 @@ open Lwt open Lwt_react +open Krobot_bus (* +-----------------------------------------------------------------+ | Command-line arguments | @@ -46,33 +47,56 @@ lwt () = | _ -> Arg.usage options usage; exit 2 in + (* Open the krobot bus. *) lwt bus = Krobot_bus.get () in - lwt () = Krobot_service.init bus ~kill:!kill ~fork:!fork "Driver" in + + (* Fork if not prevented. *) + if !fork then Lwt_daemon.daemonize (); + + (* Kill any running planner. *) + lwt () = Krobot_bus.send bus (Unix.gettimeofday (), Krobot_bus.Kill "driver") in + + (* The CAN bus, when it is available. *) + let can_opt = ref None in + + (* Handle messages. *) + E.keep + (E.map_s + (fun (ts, msg) -> + match msg with + | Kill "driver" -> + exit 0 + + | CAN frame -> begin + match !can_opt with + | Some can -> + Krobot_can_bus.send can (ts, frame) + | None -> + return () + end + + | _ -> + return ()) + (Krobot_bus.recv bus)); while_lwt true do try_lwt (* Open the CAN bus. *) lwt can = Krobot_can_bus.open_can device in - - let active, set_active = S.create true in - - (* D-Bus --> CAN *) - let ev = E.map_s (Krobot_can_bus.send can) (E.when_ active (Krobot_can.recv bus)) in + can_opt := Some can; try_lwt - (* CAN --> D-Bus *) while_lwt true do - Krobot_can_bus.recv can >>= Krobot_can.send bus + lwt (ts, frame) = Krobot_can_bus.recv can in + Krobot_bus.send bus (ts, CAN frame) done with exn -> - lwt () = Krobot_can_bus.close can in (* Make sure no more messages are sent on the CAN bus. *) - set_active false; - (* This is just here to keep a reference to [ev]. *) - E.stop ev; + can_opt := None; + lwt () = Krobot_can_bus.close can in raise_lwt exn with exn -> - lwt () = Lwt_log.error ~exn "failure" in + ignore (Lwt_log.error ~exn "failure"); if !once then exit 0 else diff --git a/info/control2011/src/interfaces/krobot-interfaces.mllib b/info/control2011/src/interfaces/krobot-interfaces.mllib deleted file mode 100644 index 612c59f..0000000 --- a/info/control2011/src/interfaces/krobot-interfaces.mllib +++ /dev/null @@ -1,6 +0,0 @@ -# OASIS_START -# DO NOT EDIT (digest: 0fb519fe846821801a9941698a640eef) -Krobot_interface_can -Krobot_interface_service -Krobot_interface_planner -# OASIS_STOP diff --git a/info/control2011/src/interfaces/krobot_interface_can.obus b/info/control2011/src/interfaces/krobot_interface_can.obus deleted file mode 100644 index 842d90c..0000000 --- a/info/control2011/src/interfaces/krobot_interface_can.obus +++ /dev/null @@ -1,22 +0,0 @@ -(* - * krobot_interface_can.obus - * ------------------------- - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -(** Interface for CAN messages *) -interface fr.krobot.CAN { - (** Signal for CAN frames: - - - when the driver receing a frame from the CAN socket, it send - this signal over D-Bus - - when the driver receive this signal it send it over the CAN - socket - *) - signal message : ( - frame : (double * uint32 * uint32 * boolean * uint32 * byte array) - ) -} diff --git a/info/control2011/src/interfaces/krobot_interface_planner.obus b/info/control2011/src/interfaces/krobot_interface_planner.obus deleted file mode 100644 index ac8f5d7..0000000 --- a/info/control2011/src/interfaces/krobot_interface_planner.obus +++ /dev/null @@ -1,39 +0,0 @@ -(* - * krobot_interface_planner.obus - * ----------------------------- - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -(** Interface for the planner. *) - -interface fr.krobot.Planner { - property_r origin : ((double * double) * (double * double)) - (** The origin of the trajectory, with the initial vector. *) - - property_rw vertices : (double * double) array - (** Property holding the current list of vertices for the planned - trajectory. *) - - method add_vertice : (vertice : (double * double)) -> () - (** Add a new vertice after all current ones to [vertices]. *) - - method simplify : (tolerance : double) -> () - (** Simplify the trajectory using the given tolerance. *) - - (** Move the robot according to the current trajectory. *) - method go : ( - rotation_speed : double, - rotation_acceleration : double, - moving_speed : double, - moving_acceleration : double - ) -> () - - method stop : () -> () - (** Stop the current trajectory. *) - - property_r moving : boolean - (** Is the robot currently following a trajectory ? *) -} diff --git a/info/control2011/src/interfaces/krobot_interface_service.obus b/info/control2011/src/interfaces/krobot_interface_service.obus deleted file mode 100644 index 6f5e940..0000000 --- a/info/control2011/src/interfaces/krobot_interface_service.obus +++ /dev/null @@ -1,20 +0,0 @@ -(* - * krobot_interface_service.obus - * ----------------------------- - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -(** Interface for krobot services. *) -interface fr.krobot.Service { - (** Make the service to exit. *) - method kill : () -> () - with { - org.freedesktop.DBus.Method.NoReply = "true" - } - - signal log : (message : string) - (** Signal emitted when the service emit a log message. *) -} diff --git a/info/control2011/src/lib/META b/info/control2011/src/lib/META index 8cab18d..dfccb8d 100644 --- a/info/control2011/src/lib/META +++ b/info/control2011/src/lib/META @@ -1,8 +1,8 @@ # OASIS_START -# DO NOT EDIT (digest: 6d4fe02a501933ad8464e70af7fcf3b1) +# DO NOT EDIT (digest: 3dcfd084b393896010b17f3aac3a6423) version = "1.0" description = "The [Kro]bot library" -requires = "lwt.unix obus krobot.interfaces" +requires = "lwt.unix lwt.react" archive(byte) = "krobot.cma" archive(native) = "krobot.cmxa" exists_if = "krobot.cma" @@ -14,14 +14,5 @@ package "can" ( archive(native) = "krobot-can.cmxa" exists_if = "krobot-can.cma" ) - -package "interfaces" ( - version = "1.0" - description = "[Kro]bot D-Bus interfaces" - requires = "obus" - archive(byte) = "krobot-interfaces.cma" - archive(native) = "krobot-interfaces.cmxa" - exists_if = "krobot-interfaces.cma" -) # OASIS_STOP diff --git a/info/control2011/src/lib/krobot.mllib b/info/control2011/src/lib/krobot.mllib index 2d6a922..a445537 100644 --- a/info/control2011/src/lib/krobot.mllib +++ b/info/control2011/src/lib/krobot.mllib @@ -1,9 +1,8 @@ # OASIS_START -# DO NOT EDIT (digest: a2debf72e72f6ae38ea62c8b35c3784d) +# DO NOT EDIT (digest: cd69d2910ad86f88b392f7a3935ab5c4) Krobot_can Krobot_bus Krobot_message -Krobot_service Krobot_geom -Krobot_planner +Krobot_config # OASIS_STOP diff --git a/info/control2011/src/lib/krobot_bus.ml b/info/control2011/src/lib/krobot_bus.ml index 057b8dc..a77f60e 100644 --- a/info/control2011/src/lib/krobot_bus.ml +++ b/info/control2011/src/lib/krobot_bus.ml @@ -7,45 +7,165 @@ * This file is a part of [kro]bot. *) -let section = Lwt_log.Section.make "bus" +open Lwt +open Lwt_react +open Krobot_geom -type t = OBus_bus.t +let section = Lwt_log.Section.make "krobot(bus)" +let port = 50000 -external of_bus : OBus_bus.t -> t = "%identity" -external to_bus : t -> OBus_bus.t = "%identity" +(* +-----------------------------------------------------------------+ + | Types | + +-----------------------------------------------------------------+ *) -let default_address = [OBus_address.make "unix" [("abstract", "krobot")]] +type message = + | CAN of Krobot_can.frame + | Log of string + | Send + | Kill of string + | Trajectory_origin of vertice * vector + | Trajectory_vertices of vertice list + | Trajectory_set_vertices of vertice list + | Trajectory_add_vertice of vertice + | Trajectory_simplify of float + | Trajectory_go of float * float * float * float + | Trajectory_stop + | Trajectory_moving of bool -let address = - match try Some(Sys.getenv "DBUS_KROBOT_BUS_ADDRESS") with Not_found -> None with - | Some str -> begin +type t = { + oc : Lwt_io.output_channel; + recv : (float * message) event; +} + +(* +-----------------------------------------------------------------+ + | Message printer | + +-----------------------------------------------------------------+ *) + +open Printf + +let string_of_vertice v = + sprintf "{ x = %f; y = %f }" v.x v.y + +let string_of_vector v = + sprintf "{ vx = %f; vy = %f }" v.vx v.vy + +let string_of_message = function + | CAN frame -> + sprintf + "CAN %s" + (Krobot_can.string_of_frame frame) + | Log str -> + sprintf + "Log %S" + str + | Send -> + "Send" + | Kill name -> + sprintf + "Kill %S" + name + | Trajectory_origin(o, v) -> + sprintf + "Trajectory_origin(%s, %s)" + (string_of_vertice o) + (string_of_vector v) + | Trajectory_vertices l -> + sprintf + "Trajectory_vertices [%s]" + (String.concat "; " (List.map string_of_vertice l)) + | Trajectory_set_vertices l -> + sprintf + "Trajectory_set_vertices [%s]" + (String.concat "; " (List.map string_of_vertice l)) + | Trajectory_add_vertice v -> + sprintf + "Trajectory_add_vertice %s" + (string_of_vertice v) + | Trajectory_simplify tolerance -> + sprintf + "Trajectory_simplify %f" + tolerance + | Trajectory_go(a, b, c, d) -> + sprintf + "Trajectory_go(%f, %f, %f, %f)" + a b c d + | Trajectory_stop -> + "Trajectory_stop" + | Trajectory_moving b -> + sprintf + "Trajectory_moving %B" + b + +(* +-----------------------------------------------------------------+ + | Sending/receiving messages | + +-----------------------------------------------------------------+ *) + +let send bus v = Lwt_io.write_value bus.oc v +let recv bus = bus.recv + +(* +-----------------------------------------------------------------+ + | Dispatching incomming messages | + +-----------------------------------------------------------------+ *) + +let dispatch ic emit = + try_lwt + while_lwt true do + (* Read one message. *) + lwt v = Lwt_io.read_value ic in + + (* Emit it. *) + begin try - OBus_address.of_string str - with OBus_address.Parse_failure(str, pos, err) -> - ignore (Lwt_log.error_f "The environment variable DBUS_KROBOT_BUS_ADDRESS contains an invalid D-Bus address: \"%s\", at position %d: %s" str pos err); - default_address - end - | None -> - default_address + emit v + with exn -> + ignore (Lwt_log.error ~section ~exn "message handler failed with") + end; + + return () + done + with exn -> + ignore (Lwt_log.error ~section ~exn "lost connection"); + exit 1 + +(* +-----------------------------------------------------------------+ + | Creation | + +-----------------------------------------------------------------+ *) let bus = lazy( try_lwt - lwt () = Lwt_log.info "openning the D-Bus krobot bus" in - OBus_bus.of_addresses address + (* Open a connection to the local HUB. *) + lwt ic, oc = Lwt_io.open_connection (Unix.ADDR_INET(Unix.inet_addr_loopback, port)) in + + (* The event for incomming message. *) + let recv, emit = E.create () in + + (* Dispatch message forever. *) + ignore (dispatch ic emit); + + (* Create the bus. *) + let bus = { oc; recv } in + + (* Send logs over the bus. *) + let logger = + Lwt_log.make + (fun section level lines -> + let buf = Buffer.create 42 in + List.iter + (fun line -> + Buffer.clear buf; + Lwt_log.render ~buffer:buf ~template:"$(name)[$(section)]: $(message)" ~section ~level ~message:line; + ignore (send bus (Unix.gettimeofday (), Log(Buffer.contents buf)))) + lines; + return ()) + return + in + + Lwt_log.default := Lwt_log.broadcast [!Lwt_log.default; logger]; + + return bus with exn -> - lwt () = Lwt_log.error_f ~section ~exn "failed to connect to the D-Bus krobot bus at address \"%s\"" (OBus_address.to_string address) in + ignore (Lwt_log.error ~section ~exn "failed to connect to the local hub"); exit 1 ) let get () = Lazy.force bus - -(* We put that here because all programs use this module. *) -let () = - Printexc.register_printer - (function - | Unix.Unix_error(error, func, "") -> - Some(Printf.sprintf "%s: %s" func (Unix.error_message error)) - | Unix.Unix_error(error, func, arg) -> - Some(Printf.sprintf "%s(%S): %s" func arg (Unix.error_message error)) - | _ -> - None) diff --git a/info/control2011/src/lib/krobot_bus.mli b/info/control2011/src/lib/krobot_bus.mli index 724c1d1..dccfb9f 100644 --- a/info/control2011/src/lib/krobot_bus.mli +++ b/info/control2011/src/lib/krobot_bus.mli @@ -9,12 +9,54 @@ (** The krobot bus. *) -type t = private OBus_bus.t - (** Type of the krobot bus. *) +open Krobot_geom -external of_bus : OBus_bus.t -> t = "%identity" -external to_bus : t -> OBus_bus.t = "%identity" +type t + (** Type of a krobot bus connected to the local HUB. *) val get : unit -> t Lwt.t (** [get ()] returns the krobot bus. It exits the program on - errors. *) + error. *) + +(** Type of message exchanged over the bus. *) +type message = + | CAN of Krobot_can.frame + (** A CAN frame. *) + | Log of string + (** A log message. *) + | Send + (** Ask for sending parameters. *) + | Kill of string + (** Kill the given service. *) + + (** Trajectory messages. *) + + | Trajectory_origin of vertice * vector + (** The origin of the trajectory with the initial direction + vector. *) + | Trajectory_vertices of vertice list + (** The list of vertices for the planned trajectory. *) + | Trajectory_set_vertices of vertice list + (** Sets the trajectory. *) + | Trajectory_add_vertice of vertice + (** Add a vertice to the trajectory. *) + | Trajectory_simplify of float + (** Simplify the trajectory with the given tolerance. *) + | Trajectory_go of float * float * float * float + (** [Trajectory_go(rotation_speed, rotation_acceleration, + moving_speed, moving_acceleration)]. *) + | Trajectory_stop + (** Stop the current trajectory. *) + | Trajectory_moving of bool + (** Is the robot following a trajectory ? *) + +val string_of_message : message -> string + (** Returns a string representation of the given message. *) + +val send : t -> (float * message) -> unit Lwt.t + (** [send bus (timestamp, message)] sends a message over the krobot + bus. *) + +val recv : t -> (float * message) React.event + (** [recv bus] returns the event which receive messages from the + krobot bus. *) diff --git a/info/control2011/src/lib/krobot_can.ml b/info/control2011/src/lib/krobot_can.ml index c5d9094..feb997f 100644 --- a/info/control2011/src/lib/krobot_can.ml +++ b/info/control2011/src/lib/krobot_can.ml @@ -147,72 +147,3 @@ let put_float32 str ofs v = str.[ofs + 1] <- Char.unsafe_chr (Int32.to_int (Int32.shift_right v 8)); str.[ofs + 2] <- Char.unsafe_chr (Int32.to_int (Int32.shift_right v 16)); str.[ofs + 3] <- Char.unsafe_chr (Int32.to_int (Int32.shift_right v 24)) - -(* +-----------------------------------------------------------------+ - | D-Bus value conversion | - +-----------------------------------------------------------------+ *) - -open OBus_value - -let typ = C.structure (C.seq6 C.basic_double C.basic_uint32 C.basic_uint32 C.basic_boolean C.basic_uint32 C.byte_array) - -let value_of_frame (timestamp, frame) = - C.make_single - typ - (timestamp, - Int32.of_int frame.identifier, - (match frame.kind with - | Data -> 0l - | Error -> 1l), - frame.remote, - (match frame.format with - | F11bits -> 0l - | F29bits -> 1l), - frame.data) - -let frame_of_tuple (timestamp, identifier, kind, remote, format, data) = - let identifier = Int32.to_int identifier in - let kind = - match kind with - | 0l -> Data - | 1l -> Error - | n -> Printf.ksprintf failwith "Krobot_can.frame_of_value: invalid frame kind (%ld)" n - in - let format = - match format with - | 0l -> F11bits - | 1l -> F29bits - | n -> Printf.ksprintf failwith "Krobot_can.frame_of_value: invalid frame format (%ld)" n - in - (timestamp, frame ~identifier ~kind ~remote ~format ~data) - -let frame_of_value v = - frame_of_tuple (C.cast_single typ v) - -(* +-----------------------------------------------------------------+ - | Sending/receiving frames | - +-----------------------------------------------------------------+ *) - -let send bus arg = - OBus_connection.send_message - (Krobot_bus.to_bus bus) - (OBus_message.signal - ~path:["fr"; "krobot"; "CAN"] - ~interface:"fr.krobot.CAN" - ~member:"message" - [value_of_frame arg]) - -let recv bus = - let proxy = OBus_proxy.make (OBus_peer.anonymous (Krobot_bus.to_bus bus)) ["fr"; "krobot"; "CAN"] in - E.fmap - (fun (ctx, frame) -> - (* Filter messages comming from us. *) - if OBus_peer.name (OBus_context.sender ctx) = OBus_bus.name (Krobot_bus.to_bus bus) then - None - else - Some frame) - (E.delay - (OBus_signal.connect - (OBus_signal.with_context - (OBus_signal.map frame_of_tuple - (OBus_signal.make Krobot_interface_can.Fr_krobot_CAN.s_message proxy))))) diff --git a/info/control2011/src/lib/krobot_can.mli b/info/control2011/src/lib/krobot_can.mli index a0f9869..beb6d5a 100644 --- a/info/control2011/src/lib/krobot_can.mli +++ b/info/control2011/src/lib/krobot_can.mli @@ -88,24 +88,3 @@ val put_sint32 : string -> int -> int -> unit val put_uint32 : string -> int -> int -> unit val put_float32 : string -> int -> float -> unit - -(** {6 D-Bus frame conversion} *) - -val value_of_frame : float * frame -> OBus_value.V.single - (** Converts a can frame into a D-Bus structure. *) - -val frame_of_value : OBus_value.V.single -> float * frame - (** Converts a D-Bus structure into a can frame. *) - -val frame_of_tuple : float * int32 * int32 * bool * int32 * string -> float * frame - (** Converts a tuple into a can frame. *) - -(** {6 Sending/receiving frames} *) - -val send : Krobot_bus.t -> (float * frame) -> unit Lwt.t - (** [send bus (timestamp, frame)] sends the given frame over - D-Bus. *) - -val recv : Krobot_bus.t -> (float * frame) React.event - (** [recv bus] returns is the event which occurs whan a CAN frame is - received. *) diff --git a/info/control2011/src/lib/krobot_geom.ml b/info/control2011/src/lib/krobot_geom.ml index 1f8a016..1c84bf3 100644 --- a/info/control2011/src/lib/krobot_geom.ml +++ b/info/control2011/src/lib/krobot_geom.ml @@ -9,6 +9,18 @@ let sqr x = x *. x +let pi = 4. *. atan 1. + +let math_mod_float a b = + let b2 = b /. 2. in + let modf = mod_float a b in + if modf > b2 then + modf -. b + else if modf < -. b2 then + modf +. b + else + modf + (* +-----------------------------------------------------------------+ | Vectors | +-----------------------------------------------------------------+ *) diff --git a/info/control2011/src/lib/krobot_geom.mli b/info/control2011/src/lib/krobot_geom.mli index c611dd6..59bee62 100644 --- a/info/control2011/src/lib/krobot_geom.mli +++ b/info/control2011/src/lib/krobot_geom.mli @@ -11,6 +11,12 @@ (** {6 Basic geometry} *) +val pi : float + (** 3.14... *) + +val math_mod_float : float -> float -> float + (** Same as [mod_float] but always returns a positive number. *) + type vector = { vx : float; vy : float } type vertice = { x : float; y : float } diff --git a/info/control2011/src/lib/krobot_message.ml b/info/control2011/src/lib/krobot_message.ml index c9da849..62aff7a 100644 --- a/info/control2011/src/lib/krobot_message.ml +++ b/info/control2011/src/lib/krobot_message.ml @@ -415,5 +415,15 @@ let decode frame = | Sending/receiving messages | +-----------------------------------------------------------------+ *) -let send bus (timestamp, msg) = Krobot_can.send bus (timestamp, encode msg) -let recv bus = E.map (fun (timestamp, frame) -> (timestamp, decode frame)) (Krobot_can.recv bus) +let send bus (timestamp, msg) = + Krobot_bus.send bus (timestamp, Krobot_bus.CAN(encode msg)) + +let recv bus = + E.fmap + (fun (timestamp, message) -> + match message with + | Krobot_bus.CAN frame -> + Some(timestamp, decode frame) + | _ -> + None) + (Krobot_bus.recv bus) diff --git a/info/control2011/src/lib/krobot_message.mli b/info/control2011/src/lib/krobot_message.mli index 991d2b4..557994c 100644 --- a/info/control2011/src/lib/krobot_message.mli +++ b/info/control2011/src/lib/krobot_message.mli @@ -7,7 +7,7 @@ * This file is a part of [kro]bot. *) -(** Krobot messages. *) +(** Krobot CAN messages. *) type direction = Forward | Backward (** Type of directions. *) diff --git a/info/control2011/src/lib/krobot_planner.ml b/info/control2011/src/lib/krobot_planner.ml deleted file mode 100644 index c1fc2d1..0000000 --- a/info/control2011/src/lib/krobot_planner.ml +++ /dev/null @@ -1,44 +0,0 @@ -(* - * krobot_planner.ml - * ----------------- - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -open Lwt -open Lwt_react -open Krobot_geom -open Krobot_interface_planner.Fr_krobot_Planner - -type t = Krobot_bus.t - -let proxy bus = - OBus_proxy.make (OBus_peer.make (Krobot_bus.to_bus bus) "fr.krobot.Service.Planner") ["fr"; "krobot"; "Planner"] - -let origin bus = - OBus_property.map_r - (fun ((x, y), (vx, vy)) -> ({ x; y }, ({ vx; vy }))) - (OBus_property.make p_origin (proxy bus)) - -let vertices bus = - OBus_property.map_rw - (List.map (fun (x, y) -> { x; y })) - (List.map (fun { x; y } -> (x, y))) - (OBus_property.make p_vertices (proxy bus)) - -let add_vertice bus { x; y } = - OBus_method.call m_add_vertice (proxy bus) (x, y) - -let simplify bus tolerance = - OBus_method.call m_simplify (proxy bus) tolerance - -let moving bus = - OBus_property.make p_moving (proxy bus) - -let go bus a b c d = - OBus_method.call m_go (proxy bus) (a, b, c, d) - -let stop bus = - OBus_method.call m_stop (proxy bus) () diff --git a/info/control2011/src/lib/krobot_planner.mli b/info/control2011/src/lib/krobot_planner.mli deleted file mode 100644 index 077956e..0000000 --- a/info/control2011/src/lib/krobot_planner.mli +++ /dev/null @@ -1,33 +0,0 @@ -(* - * krobot_planner.mli - * ------------------ - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -type t = Krobot_bus.t - (** Type of the planner. *) - -val origin : t -> (Krobot_geom.vertice * Krobot_geom.vector, [ `readable ]) OBus_property.t - (** The origin of the trajectory. *) - -val vertices : t -> (Krobot_geom.vertice list, [ `readable | `writable ]) OBus_property.t - (** The property holding the current trajectory. *) - -val add_vertice : t -> Krobot_geom.vertice -> unit Lwt.t - (** Add a vertice at the end of the current trajectory. *) - -val simplify : t -> float -> unit Lwt.t - (** [simplify planner tolerance] simplify the trajectory. *) - -val moving : t -> (bool, [ `readable ]) OBus_property.t - (** Is the robot currently following a trajectory ? *) - -val go : t -> float -> float -> float -> float -> unit Lwt.t - (** [go planner rotation_speed rotation_acceleration moving_speed - moving_acceleration] make the robot to follow the trajectory. *) - -val stop : t -> unit Lwt.t - (** Stop the current trajectory. *) diff --git a/info/control2011/src/lib/krobot_service.ml b/info/control2011/src/lib/krobot_service.ml deleted file mode 100644 index 9593dee..0000000 --- a/info/control2011/src/lib/krobot_service.ml +++ /dev/null @@ -1,145 +0,0 @@ -(* - * krobot_service.ml - * ----------------- - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -include OBus_proxy.Private - -let section = Lwt_log.Section.make "service" - -(* +-----------------------------------------------------------------+ - | Service management | - +-----------------------------------------------------------------+ *) - -open Lwt -open Lwt_react -open Krobot_interface_service.Fr_krobot_Service - -let all bus = - OBus_proxy.make - (OBus_peer.anonymous (Krobot_bus.to_bus bus)) - ["fr"; "krobot"; "Service"] - -let make bus name = - if name = "" then - all bus - else - OBus_proxy.make - (OBus_peer.make - (Krobot_bus.to_bus bus) - (Printf.sprintf "fr.krobot.Service.%s" name)) - ["fr"; "krobot"; "Service"] - -let name service = - let s = OBus_proxy.name service in - let i = String.rindex s '.' in - String.sub s (i + 1) (String.length s - (i + 1)) - -let list bus = - lwt names = OBus_bus.list_names (Krobot_bus.to_bus bus) in - return - (List.map - (fun name -> - OBus_proxy.make - (OBus_peer.make (Krobot_bus.to_bus bus) name) - ["fr"; "krobot"; "Service"]) - (List.sort - String.compare - (List.filter - (fun name -> - String.sub name 0 (String.rindex name '.') = "fr.krobot.Service") - names))) - -let monitor bus = - lwt e = OBus_signal.connect (OBus_bus.name_owner_changed (Krobot_bus.to_bus bus)) in - lwt l = list bus in - return (S.hold l (E.map_s (fun _ -> list bus) e)) - -let kill' bus name = - try_lwt - lwt owner = OBus_bus.get_name_owner bus name in - let proxy = OBus_proxy.make (OBus_peer.make bus owner) ["fr"; "krobot"; "Service"] in - OBus_method.call_no_reply m_kill proxy () - with OBus_bus.Name_has_no_owner _ -> - return () - -let kill service = - kill' (OBus_proxy.connection service) (OBus_proxy.name service) - -let log service = - OBus_signal.make s_log service - -(* +-----------------------------------------------------------------+ - | Creating services | - +-----------------------------------------------------------------+ *) - -open Krobot_interface_service.Fr_krobot_Service - -let init bus ?(fork=true) ?(kill=false) name = - let dbus_name = Printf.sprintf "fr.krobot.Service.%s" name in - - (* Kill other instances. *) - lwt () = - if kill then - lwt () = kill' (Krobot_bus.to_bus bus) dbus_name in - exit 0 - else - return () - in - - (* Exit the program when we lost the name. *) - lwt () = - OBus_signal.connect (OBus_bus.name_lost (Krobot_bus.to_bus bus)) - >|= E.map (fun lost_name -> if dbus_name = lost_name then exit 0) - >|= E.keep - in - - (* Daemonize or not. *) - lwt () = - if fork then begin - lwt () = Lwt_log.notice_f ~section "starting %s in daemon mode" name in - Lwt_daemon.daemonize (); - return () - end else - Lwt_log.notice_f ~section "starting %s in foreground mode" name - in - - (* Create the service object and export it. *) - let obj = OBus_object.make ~interfaces:[make { m_kill = (fun obj () -> exit 0) }] ["fr"; "krobot"; "Service"] in - OBus_object.attach obj (); - OBus_object.export (Krobot_bus.to_bus bus) obj; - - (* Send logs over D-Bus. *) - let dbus_logger = - Lwt_log.make - (fun section level lines -> - let buf = Buffer.create 42 in - let lines = - List.map - (fun line -> - Buffer.clear buf; - Lwt_log.render ~buffer:buf ~template:"$(name)[$(section)]: $(message)" ~section ~level ~message:line; - Buffer.contents buf) - lines - in - OBus_signal.emit s_log obj (String.concat "\n" lines)) - return - in - - Lwt_log.default := Lwt_log.broadcast [!Lwt_log.default; dbus_logger]; - - (* Register the program on the bus. *) - lwt () = - OBus_bus.request_name (Krobot_bus.to_bus bus) ~allow_replacement:true ~replace_existing:true dbus_name >>= function - | `Primary_owner -> - return () - | _ -> - lwt () = Lwt_log.error_f ~section "cannot obtain the name %S on D-Bus" dbus_name in - exit 1 - in - - return () diff --git a/info/control2011/src/lib/krobot_service.mli b/info/control2011/src/lib/krobot_service.mli deleted file mode 100644 index f6a64fb..0000000 --- a/info/control2011/src/lib/krobot_service.mli +++ /dev/null @@ -1,41 +0,0 @@ -(* - * krobot_service.mli - * ------------------ - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -include OBus_proxy.Private - -val make : Krobot_bus.t -> string -> t - (** [make bus name pid] creates a service proxy from its name. *) - -val all : Krobot_bus.t -> t - (** Proxy that represent all running services. You can use it to - receive logs from all services. *) - -val name : t -> string - (** Returns the name of the given service. *) - -val list : Krobot_bus.t -> t list Lwt.t - (** List all available services on the bus. *) - -val monitor : Krobot_bus.t -> t list React.signal Lwt.t - (** Returns the signal holding the sorted list of services on the - bus. *) - -val kill : t -> unit Lwt.t - (** [kill service] kills the given service. It does nothing if the - service is not running. *) - -val log : t -> string OBus_signal.t - (** [log service] is the D-Bus signal which occurs when [service] - emit a log message. *) - -val init : Krobot_bus.t -> ?fork : bool -> ?kill : bool -> string -> unit Lwt.t - (** [init ?fork ?kill name] initialises a D-Bus service using name - [name]. If [fork] is [true] (the default) then the program is - daemonized. If [kill] is [true] any service with name [name] is - killed then the program is exited. It defaults to [false]. *) diff --git a/info/control2011/src/services/fr.krobot.Service.Planner.service.ab b/info/control2011/src/services/fr.krobot.Service.Planner.service.ab deleted file mode 100644 index 13dc4d3..0000000 --- a/info/control2011/src/services/fr.krobot.Service.Planner.service.ab +++ /dev/null @@ -1,3 +0,0 @@ -[D-BUS Service] -Name=fr.krobot.Service.Planner -Exec=$(bindir)/krobot-service-planner diff --git a/info/control2011/src/services/krobot_service_planner.ml b/info/control2011/src/services/krobot_service_planner.ml deleted file mode 100644 index 431a08d..0000000 --- a/info/control2011/src/services/krobot_service_planner.ml +++ /dev/null @@ -1,343 +0,0 @@ -(* - * krobot_service_planner.ml - * ------------------------- - * Copyright : (c) 2011, Jeremie Dimino <je...@di...> - * Licence : BSD3 - * - * This file is a part of [kro]bot. - *) - -(* The trajectory planner. *) - -open Lwt -open Lwt_react -open Krobot_geom -open Krobot_config -open Krobot_message -open Krobot_interface_planner.Fr_krobot_Planner - -let section = Lwt_log.Section.make "krobot(planner)" - -let pi = 4. *. atan 1. - -let math_mod_float a b = - let b2 = b /. 2. in - let modf = mod_float a b in - if modf > b2 then - modf -. b - else if modf < -. b2 then - modf +. b - else - modf;; - -(* +-----------------------------------------------------------------+ - | Types | - +-----------------------------------------------------------------+ *) - -type planner = { - bus : Krobot_bus.t; - (* The message bus used to communicate with the robot. *) - - obus : planner OBus_object.t; - (* The D-Bus object attached to this planner. *) - - origin : (vertice * vector) signal; - (* If the robot is moving, this is the origin of the current - trajectory with the initial direction vector, otherwise it is the - current position with the current direction vector. *) - - set_origin : (vertice * vector) -> unit; - (* Set the origin of the trajectory. *) - - vertices : vertice list signal; - (* The list of vertices for the trajectory. *) - - set_vertices : vertice list -> unit; - (* Set the list of vertices. *) - - moving : bool signal; - (* Is the robot moving ? *) - - set_moving : bool -> unit; - (* Set the moving status. *) - - mutable motors_moving : bool; - (* Are the motor currently active ? *) - - mutable mover : unit Lwt.t; - (* The thread moving the robot. *) - - mutable position : vertice; - (* The position of the robot on the board. *) - - mutable orientation : float; - (* The orientation of the robot. *) - - mutable event : unit event; - (* Event kept in the planner. *) -} - -(* +-----------------------------------------------------------------+ - | Primitives | - +-----------------------------------------------------------------+ *) - -let add_vertice planner vertice = - ... [truncated message content] |
From: Benjamin A. <Ba...@us...> - 2011-04-18 23:49:14
|
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 3c5104a9beb21ba05f513b15c7798075364ca875 (commit) via f22dafb3f0864a8b1e53343db7019337181676ca (commit) via b1cc4511212b197108a39fe2fe35f73c7b992e05 (commit) from 9b656fa3148ddfc5179e956ab19b4c0bba7f03c7 (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 3c5104a9beb21ba05f513b15c7798075364ca875 Merge: f22dafb3f0864a8b1e53343db7019337181676ca 9b656fa3148ddfc5179e956ab19b4c0bba7f03c7 Author: Benjamin Aupetit <au...@cr...> Date: Tue Apr 19 01:48:46 2011 +0200 Merge branch 'master' of ssh://krobot.git.sourceforge.net/gitroot/krobot/krobot commit f22dafb3f0864a8b1e53343db7019337181676ca Author: Benjamin Aupetit <au...@cr...> Date: Tue Apr 19 01:47:45 2011 +0200 [meca] Solving some bugs commit b1cc4511212b197108a39fe2fe35f73c7b992e05 Author: Benjamin Aupetit <au...@cr...> Date: Tue Apr 19 01:46:54 2011 +0200 [meca] Adding drawing for HPC ----------------------------------------------------------------------- Changes: diff --git a/meca/2011_Senior/SupportMiroir/Mat_Balise.CATProduct b/meca/2011_Senior/SupportMiroir/Mat_Balise.CATProduct index 4cdce1b..25a9e4c 100644 Binary files a/meca/2011_Senior/SupportMiroir/Mat_Balise.CATProduct and b/meca/2011_Senior/SupportMiroir/Mat_Balise.CATProduct differ diff --git a/meca/2011_Senior/ascenceurs/Ascenseur_axe_glissiere.CATPart b/meca/2011_Senior/ascenceurs/Ascenseur_axe_glissiere.CATPart index f96e239..7b62622 100644 Binary files a/meca/2011_Senior/ascenceurs/Ascenseur_axe_glissiere.CATPart and b/meca/2011_Senior/ascenceurs/Ascenseur_axe_glissiere.CATPart differ diff --git a/meca/2011_Senior/ascenceurs/Ascenseur_plaque.CATPart b/meca/2011_Senior/ascenceurs/Ascenseur_plaque.CATPart index a6e43cb..ad3c63a 100644 Binary files a/meca/2011_Senior/ascenceurs/Ascenseur_plaque.CATPart and b/meca/2011_Senior/ascenceurs/Ascenseur_plaque.CATPart differ diff --git a/meca/2011_Senior/ascenceurs/Poulie_bas_avec_support.CATProduct b/meca/2011_Senior/ascenceurs/Poulie_bas_avec_support.CATProduct index 7853e4b..c9b82fc 100644 Binary files a/meca/2011_Senior/ascenceurs/Poulie_bas_avec_support.CATProduct and b/meca/2011_Senior/ascenceurs/Poulie_bas_avec_support.CATProduct differ diff --git a/meca/2011_Senior/ascenceurs/ascenseur.CATProduct b/meca/2011_Senior/ascenceurs/ascenseur.CATProduct index 33002aa..2edafc5 100644 Binary files a/meca/2011_Senior/ascenceurs/ascenseur.CATProduct and b/meca/2011_Senior/ascenceurs/ascenseur.CATProduct differ diff --git a/meca/2011_Senior/ascenceurs/serre-courroie.CATPart b/meca/2011_Senior/ascenceurs/serre-courroie.CATPart index 023b5ff..14d6826 100644 Binary files a/meca/2011_Senior/ascenceurs/serre-courroie.CATPart and b/meca/2011_Senior/ascenceurs/serre-courroie.CATPart differ diff --git a/meca/2011_Senior/bati/base.CATPart b/meca/2011_Senior/bati/base.CATPart index e22452c..72651a5 100644 Binary files a/meca/2011_Senior/bati/base.CATPart and b/meca/2011_Senior/bati/base.CATPart differ diff --git a/meca/2011_Senior/bati/plaque2.CATPart b/meca/2011_Senior/bati/plaque2.CATPart index 6baa75b..d67e6ec 100644 Binary files a/meca/2011_Senior/bati/plaque2.CATPart and b/meca/2011_Senior/bati/plaque2.CATPart differ diff --git a/meca/2011_Senior/bati/plaque3.CATPart b/meca/2011_Senior/bati/plaque3.CATPart index 9917255..5750f9c 100644 Binary files a/meca/2011_Senior/bati/plaque3.CATPart and b/meca/2011_Senior/bati/plaque3.CATPart differ diff --git a/meca/2011_Senior/bati/plaque4.CATPart b/meca/2011_Senior/bati/plaque4.CATPart index e38d358..ae720aa 100644 Binary files a/meca/2011_Senior/bati/plaque4.CATPart and b/meca/2011_Senior/bati/plaque4.CATPart differ diff --git a/meca/2011_Senior/bati/plaque5.CATPart b/meca/2011_Senior/bati/plaque5.CATPart index d3620ce..7710d0f 100644 Binary files a/meca/2011_Senior/bati/plaque5.CATPart and b/meca/2011_Senior/bati/plaque5.CATPart differ diff --git a/meca/2011_Senior/cartes/cartes.CATProduct b/meca/2011_Senior/cartes/cartes.CATProduct index 5b125e3..146063b 100644 Binary files a/meca/2011_Senior/cartes/cartes.CATProduct and b/meca/2011_Senior/cartes/cartes.CATProduct differ diff --git a/meca/2011_Senior/cartes/entretoises-carte.CATProduct b/meca/2011_Senior/cartes/entretoises-carte.CATProduct index 0db4f8a..1f29607 100644 Binary files a/meca/2011_Senior/cartes/entretoises-carte.CATProduct and b/meca/2011_Senior/cartes/entretoises-carte.CATProduct differ diff --git a/meca/2011_Senior/cartes/entretoises-cartes.CATProduct b/meca/2011_Senior/cartes/entretoises-cartes.CATProduct index 3a216eb..3f7a070 100644 Binary files a/meca/2011_Senior/cartes/entretoises-cartes.CATProduct and b/meca/2011_Senior/cartes/entretoises-cartes.CATProduct differ diff --git a/meca/2011_Senior/divers/webcam.CATProduct b/meca/2011_Senior/divers/webcam.CATProduct index 7d17615..771557b 100644 Binary files a/meca/2011_Senior/divers/webcam.CATProduct and b/meca/2011_Senior/divers/webcam.CATProduct differ diff --git a/meca/2011_Senior/etages/Etage_1.CATProduct b/meca/2011_Senior/etages/Etage_1.CATProduct index eaa9147..306bce0 100644 Binary files a/meca/2011_Senior/etages/Etage_1.CATProduct and b/meca/2011_Senior/etages/Etage_1.CATProduct differ diff --git a/meca/2011_Senior/etages/Etage_2.CATProduct b/meca/2011_Senior/etages/Etage_2.CATProduct index c879607..34b13e0 100644 Binary files a/meca/2011_Senior/etages/Etage_2.CATProduct and b/meca/2011_Senior/etages/Etage_2.CATProduct differ diff --git a/meca/2011_Senior/etages/Etage_3.CATProduct b/meca/2011_Senior/etages/Etage_3.CATProduct index cca64c3..a575b11 100644 Binary files a/meca/2011_Senior/etages/Etage_3.CATProduct and b/meca/2011_Senior/etages/Etage_3.CATProduct differ diff --git a/meca/2011_Senior/etages/etage1/axes.CATProduct b/meca/2011_Senior/etages/etage1/axes.CATProduct index 1d017d7..ccae73f 100644 Binary files a/meca/2011_Senior/etages/etage1/axes.CATProduct and b/meca/2011_Senior/etages/etage1/axes.CATProduct differ diff --git a/meca/2011_Senior/pinces/Pince_droite_bas.CATProduct b/meca/2011_Senior/pinces/Pince_droite_bas.CATProduct index f95599f..d982dbb 100644 Binary files a/meca/2011_Senior/pinces/Pince_droite_bas.CATProduct and b/meca/2011_Senior/pinces/Pince_droite_bas.CATProduct differ diff --git a/meca/2011_Senior/pinces/Pince_gauche_bas.CATProduct b/meca/2011_Senior/pinces/Pince_gauche_bas.CATProduct index 16c9bf4..bf33922 100644 Binary files a/meca/2011_Senior/pinces/Pince_gauche_bas.CATProduct and b/meca/2011_Senior/pinces/Pince_gauche_bas.CATProduct differ diff --git a/meca/2011_Senior/robot.CATProduct b/meca/2011_Senior/robot.CATProduct index 45714fd..cf532ee 100644 Binary files a/meca/2011_Senior/robot.CATProduct and b/meca/2011_Senior/robot.CATProduct differ diff --git a/meca/2011_Senior/roues/Assemblage BH102-40-606 et 606ZZ.CATProduct b/meca/2011_Senior/roues/Assemblage BH102-40-606 et 606ZZ.CATProduct index ba6881e..ad4c7ee 100644 Binary files a/meca/2011_Senior/roues/Assemblage BH102-40-606 et 606ZZ.CATProduct and b/meca/2011_Senior/roues/Assemblage BH102-40-606 et 606ZZ.CATProduct differ diff --git a/meca/2011_Senior/roues/Assemblage P20.CATProduct b/meca/2011_Senior/roues/Assemblage P20.CATProduct index 0b60d98..3260c8a 100644 Binary files a/meca/2011_Senior/roues/Assemblage P20.CATProduct and b/meca/2011_Senior/roues/Assemblage P20.CATProduct differ diff --git a/meca/2011_Senior/roues/Assemblage moteur.CATProduct b/meca/2011_Senior/roues/Assemblage moteur.CATProduct index 8db3a08..33bb4e4 100644 Binary files a/meca/2011_Senior/roues/Assemblage moteur.CATProduct and b/meca/2011_Senior/roues/Assemblage moteur.CATProduct differ diff --git a/meca/2011_Senior/roues/Bloc_roue.CATProduct b/meca/2011_Senior/roues/Bloc_roue.CATProduct index 907d985..679bd5e 100644 Binary files a/meca/2011_Senior/roues/Bloc_roue.CATProduct and b/meca/2011_Senior/roues/Bloc_roue.CATProduct differ diff --git a/meca/2011_Senior/roues/GuideCodeur-bloc.CATPart b/meca/2011_Senior/roues/GuideCodeur-bloc.CATPart index af528f0..c73590b 100644 Binary files a/meca/2011_Senior/roues/GuideCodeur-bloc.CATPart and b/meca/2011_Senior/roues/GuideCodeur-bloc.CATPart differ diff --git a/meca/2011_Senior/roues/P20 Arbre.CATPart b/meca/2011_Senior/roues/P20 Arbre.CATPart index dea325b..01e091a 100644 Binary files a/meca/2011_Senior/roues/P20 Arbre.CATPart and b/meca/2011_Senior/roues/P20 Arbre.CATPart differ diff --git a/meca/2011_Senior/roues/Support.CATPart b/meca/2011_Senior/roues/Support.CATPart index f6b6c04..35fec0a 100644 Binary files a/meca/2011_Senior/roues/Support.CATPart and b/meca/2011_Senior/roues/Support.CATPart differ diff --git a/meca/2011_Senior/roues/axe_codeur.CATPart b/meca/2011_Senior/roues/axe_codeur.CATPart index 8d5c28f..e8e27b8 100644 Binary files a/meca/2011_Senior/roues/axe_codeur.CATPart and b/meca/2011_Senior/roues/axe_codeur.CATPart differ diff --git a/meca/2011_Senior/roues/axe_roue.CATPart b/meca/2011_Senior/roues/axe_roue.CATPart index b904dfb..514e1c7 100644 Binary files a/meca/2011_Senior/roues/axe_roue.CATPart and b/meca/2011_Senior/roues/axe_roue.CATPart differ diff --git a/meca/2011_Senior/usinage/Axe-Ascenseur.pdf b/meca/2011_Senior/usinage/Axe-Ascenseur.pdf new file mode 100644 index 0000000..dec5308 Binary files /dev/null and b/meca/2011_Senior/usinage/Axe-Ascenseur.pdf differ diff --git a/meca/2011_Senior/usinage/Axe-Codeur.pdf b/meca/2011_Senior/usinage/Axe-Codeur.pdf new file mode 100644 index 0000000..d36491c Binary files /dev/null and b/meca/2011_Senior/usinage/Axe-Codeur.pdf differ diff --git a/meca/2011_Senior/usinage/Axe-Roue.pdf b/meca/2011_Senior/usinage/Axe-Roue.pdf new file mode 100644 index 0000000..e21b6c4 Binary files /dev/null and b/meca/2011_Senior/usinage/Axe-Roue.pdf differ diff --git a/meca/2011_Senior/usinage/Process2.CATProcess b/meca/2011_Senior/usinage/Process2.CATProcess index cb9be57..f6160d2 100644 Binary files a/meca/2011_Senior/usinage/Process2.CATProcess and b/meca/2011_Senior/usinage/Process2.CATProcess differ diff --git a/meca/2011_Senior/usinage/axe-ascenseur.CATDrawing b/meca/2011_Senior/usinage/axe-ascenseur.CATDrawing new file mode 100644 index 0000000..83bafc1 Binary files /dev/null and b/meca/2011_Senior/usinage/axe-ascenseur.CATDrawing differ diff --git a/meca/2011_Senior/usinage/axe-codeur.CATDrawing b/meca/2011_Senior/usinage/axe-codeur.CATDrawing new file mode 100644 index 0000000..b29ec59 Binary files /dev/null and b/meca/2011_Senior/usinage/axe-codeur.CATDrawing differ diff --git a/meca/2011_Senior/usinage/axe-roue.CATDrawing b/meca/2011_Senior/usinage/axe-roue.CATDrawing new file mode 100644 index 0000000..27b9d78 Binary files /dev/null and b/meca/2011_Senior/usinage/axe-roue.CATDrawing differ hooks/post-receive -- krobot |
From: Nicolas D. <Ba...@us...> - 2011-04-18 19:38:33
|
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 9b656fa3148ddfc5179e956ab19b4c0bba7f03c7 (commit) from b14add37616c83d694455ffb1ad643bae01c0fd0 (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 9b656fa3148ddfc5179e956ab19b4c0bba7f03c7 Author: Nicolas Dandrimont <Nic...@cr...> Date: Mon Apr 18 21:38:15 2011 +0200 [krobot_message_stubs] remove useless static keyword ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/lib/krobot_message_stubs.c b/info/control2011/src/lib/krobot_message_stubs.c index 0550aa1..e34c242 100644 --- a/info/control2011/src/lib/krobot_message_stubs.c +++ b/info/control2011/src/lib/krobot_message_stubs.c @@ -11,7 +11,7 @@ #include <caml/memory.h> #include <caml/alloc.h> -static struct bezier_message { +struct bezier_message { unsigned int x : 12; unsigned int y : 12; unsigned int d1 : 8; hooks/post-receive -- krobot |
From: Jérémie D. <Ba...@us...> - 2011-04-18 19:35:04
|
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 b14add37616c83d694455ffb1ad643bae01c0fd0 (commit) from 1063889e6c9547426e6f4a8322fef1f4bd8f85f7 (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 b14add37616c83d694455ffb1ad643bae01c0fd0 Author: Jérémie Dimino <je...@di...> Date: Mon Apr 18 21:34:32 2011 +0200 [info] add libkrobot.clib ----------------------------------------------------------------------- Changes: diff --git a/info/control2011/src/lib/libkrobot.clib b/info/control2011/src/lib/libkrobot.clib new file mode 100644 index 0000000..2fd3bec --- /dev/null +++ b/info/control2011/src/lib/libkrobot.clib @@ -0,0 +1,4 @@ +# OASIS_START +# DO NOT EDIT (digest: a4550602349a377958d2b340260718d0) +krobot_message_stubs.o +# OASIS_STOP hooks/post-receive -- krobot |