Revision: 7807
http://playerstage.svn.sourceforge.net/playerstage/?rev=7807&view=rev
Author: thjc
Date: 2009-06-07 07:44:40 +0000 (Sun, 07 Jun 2009)
Log Message:
-----------
applied patch 2135324: Adding VEL_HEAD command to position2d
also fixed a number of compiler warnings
Modified Paths:
--------------
code/player/trunk/client_libs/libplayerc/dev_position2d.c
code/player/trunk/client_libs/libplayerc/dev_stereo.c
code/player/trunk/client_libs/libplayerc/playerc.h
code/player/trunk/client_libs/libplayerc++/playerc++.h
code/player/trunk/client_libs/libplayerc++/position2dproxy.cc
code/player/trunk/utils/playercam/playercam.c
code/player/trunk/utils/playerprint/playerprint.cc
code/player/trunk/utils/playerv/playerv.c
code/player/trunk/utils/playerv/pv_dev_actarray.c
code/player/trunk/utils/playerv/pv_dev_bumper.c
code/player/trunk/utils/playerv/pv_dev_camera.c
code/player/trunk/utils/playerv/pv_dev_dio.c
code/player/trunk/utils/playerv/pv_dev_gripper.c
code/player/trunk/utils/playerv/pv_dev_laser.c
code/player/trunk/utils/playerv/pv_dev_map.c
code/player/trunk/utils/playerv/pv_dev_sonar.c
Modified: code/player/trunk/client_libs/libplayerc/dev_position2d.c
===================================================================
--- code/player/trunk/client_libs/libplayerc/dev_position2d.c 2009-06-07
07:21:45 UTC (rev 7806)
+++ code/player/trunk/client_libs/libplayerc/dev_position2d.c 2009-06-07
07:44:40 UTC (rev 7807)
@@ -187,6 +187,22 @@
&cmd, NULL);
}
+// Set the robot speed and heading
+int
+playerc_position2d_set_cmd_vel_head(playerc_position2d_t *device,
+ double vx, double vy, double pa, int state)
+{
+ player_position2d_cmd_vel_head_t cmd;
+
+ memset(&cmd, 0, sizeof(cmd));
+ cmd.velocity = vx;
+ cmd.angle = pa;
+
+ return playerc_client_write(device->info.client, &device->info,
+ PLAYER_POSITION2D_CMD_VEL_HEAD,
+ &cmd, NULL);
+}
+
// Set the target pose
int
playerc_position2d_set_cmd_pose_with_vel(playerc_position2d_t *device,
Modified: code/player/trunk/client_libs/libplayerc/dev_stereo.c
===================================================================
--- code/player/trunk/client_libs/libplayerc/dev_stereo.c 2009-06-07
07:21:45 UTC (rev 7806)
+++ code/player/trunk/client_libs/libplayerc/dev_stereo.c 2009-06-07
07:44:40 UTC (rev 7807)
@@ -119,17 +119,17 @@
if (device->left_channel.image)
memcpy (device->left_channel.image, s_data->left_channel.image,
device->left_channel.image_count);
else if (device->left_channel.image_count != 0)
- PLAYERC_ERR1 ("failed to allocate memory for left image, needed %d
bytes\n", sizeof (device->left_channel.image[0]) *
device->left_channel.image_count);
+ PLAYERC_ERR1 ("failed to allocate memory for left image, needed %zd
bytes\n", sizeof (device->left_channel.image[0]) *
device->left_channel.image_count);
if (device->right_channel.image)
memcpy (device->right_channel.image, s_data->right_channel.image,
device->right_channel.image_count);
else if (device->right_channel.image_count != 0)
- PLAYERC_ERR1 ("failed to allocate memory for right image, needed %d
bytes\n", sizeof (device->right_channel.image[0]) *
device->right_channel.image_count);
+ PLAYERC_ERR1 ("failed to allocate memory for right image, needed %zd
bytes\n", sizeof (device->right_channel.image[0]) *
device->right_channel.image_count);
if (device->disparity.image)
memcpy (device->disparity.image, s_data->disparity.image,
device->disparity.image_count);
else if (device->disparity.image_count != 0)
- PLAYERC_ERR1 ("failed to allocate memory for disparity image, needed %d
bytes\n", sizeof (device->disparity.image[0]) * device->disparity.image_count);
+ PLAYERC_ERR1 ("failed to allocate memory for disparity image, needed %zd
bytes\n", sizeof (device->disparity.image[0]) * device->disparity.image_count);
/* device->pointcloud.points_count = s_data->pointcloud.points_count;
device->pointcloud.points = realloc (device->pointcloud.points,
device->pointcloud.points_count * sizeof (device->pointcloud.points[0]));
Modified: code/player/trunk/client_libs/libplayerc/playerc.h
===================================================================
--- code/player/trunk/client_libs/libplayerc/playerc.h 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/client_libs/libplayerc/playerc.h 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -2722,6 +2722,15 @@
player_pose2d_t vel,
int state);
+/** Set the target speed and heading. vx : forward speed (m/s). vy : sideways
+ speed (m/s); this field is used by omni-drive robots only. pa :
+ rotational heading (rad). All speeds and angles are defined in the robot
+ coordinate system. */
+int playerc_position2d_set_cmd_vel_head(playerc_position2d_t *device,
+ double vx, double vy, double pa, int state);
+
+
+
/** Set the target pose (gx, gy, ga) is the target pose in the
odometric coordinate system. */
PLAYERC_EXPORT int playerc_position2d_set_cmd_pose(playerc_position2d_t
*device,
Modified: code/player/trunk/client_libs/libplayerc++/playerc++.h
===================================================================
--- code/player/trunk/client_libs/libplayerc++/playerc++.h 2009-06-07
07:21:45 UTC (rev 7806)
+++ code/player/trunk/client_libs/libplayerc++/playerc++.h 2009-06-07
07:44:40 UTC (rev 7807)
@@ -1844,6 +1844,17 @@
void SetSpeed(player_pose2d_t vel)
{ return SetSpeed(vel.px, vel.py, vel.pa);}
+ /// Send a motor command for velocity/heading control mode.
+ /// Specify the forward and sideways velocity (m/sec), and angular
+ /// heading (rads).
+ void SetVelHead(double aXSpeed, double aYSpeed, double aYawHead);
+
+ /// Same as the previous SetVelHead(), but doesn't take the yspeed speed
+ /// (so use this one for non-holonomic robots).
+ void SetVelHead(double aXSpeed, double aYawHead)
+ { return SetVelHead(aXSpeed, 0, aYawHead);}
+
+
/// Send a motor command for position control mode. Specify the
/// desired pose of the robot as a player_pose_t.
/// desired motion speed as a player_pose_t.
Modified: code/player/trunk/client_libs/libplayerc++/position2dproxy.cc
===================================================================
--- code/player/trunk/client_libs/libplayerc++/position2dproxy.cc
2009-06-07 07:21:45 UTC (rev 7806)
+++ code/player/trunk/client_libs/libplayerc++/position2dproxy.cc
2009-06-07 07:44:40 UTC (rev 7807)
@@ -100,7 +100,14 @@
playerc_position2d_set_cmd_vel(mDevice,aXSpeed,aYSpeed,aYawSpeed,1);
}
+void
+Position2dProxy::SetVelHead(double aXSpeed, double aYSpeed, double aYawHead)
+{
+ scoped_lock_t lock(mPc->mMutex);
+ playerc_position2d_set_cmd_vel_head(mDevice,aXSpeed,aYSpeed,aYawHead,1);
+}
+
void Position2dProxy::GoTo(player_pose2d_t pos, player_pose2d_t vel)
{
scoped_lock_t lock(mPc->mMutex);
Modified: code/player/trunk/utils/playercam/playercam.c
===================================================================
--- code/player/trunk/utils/playercam/playercam.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playercam/playercam.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -120,7 +120,7 @@
int
get_options(int argc, char **argv)
{
- int ch=0, errflg=0;
+ int ch=0;
const char* optflags = "i:h:p:r:b:t:";
while((ch=getopt(argc, argv, optflags))!=-1)
@@ -248,8 +248,6 @@
{
GdkEventButton *bevent = (GdkEventButton *)event;
int x,y,o;
- int width, height, rowstride, n_channels;
- guchar *pixels, *p;
switch ((gint)event->type)
{
@@ -448,6 +446,8 @@
playerc_client_datamode(g_client,PLAYER_DATAMODE_PULL);
playerc_client_set_replace_rule(g_client,-1,-1,PLAYER_MSGTYPE_DATA,-1,1);
+
+ return 0;
}
int
@@ -521,6 +521,7 @@
g_print("ERROR reading player g_client\n");
//exit(-1);
}
+ return 0;
}
int
@@ -538,4 +539,5 @@
}
playerc_client_disconnect(g_client);
playerc_client_destroy(g_client);
+ return 0;
}
Modified: code/player/trunk/utils/playerprint/playerprint.cc
===================================================================
--- code/player/trunk/utils/playerprint/playerprint.cc 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerprint/playerprint.cc 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -121,7 +121,7 @@
int
get_options(int argc, char **argv)
{
- int ch=0, errflg=0;
+ int ch=0;
const char* optflags = "i:h:p:r:t:";
while((ch=getopt(argc, argv, optflags))!=-1)
@@ -170,9 +170,9 @@
exit(-1);
}
- try
+ try
{
-
+
ClientProxy* cp;
// connect to Player
@@ -193,7 +193,7 @@
// break;
case PLAYER_ACTARRAY_CODE:
cp = (ClientProxy*)new ActArrayProxy(&client,g_index);
- try
+ try
{
reinterpret_cast<ActArrayProxy*> (cp)->RequestGeometry();
}
Modified: code/player/trunk/utils/playerv/playerv.c
===================================================================
--- code/player/trunk/utils/playerv/playerv.c 2009-06-07 07:21:45 UTC (rev
7806)
+++ code/player/trunk/utils/playerv/playerv.c 2009-06-07 07:44:40 UTC (rev
7807)
@@ -211,7 +211,7 @@
if(rate == 0.0)
{
- printf("Setting delivery mode to PLAYER_DATAMODE_PUSH\n", host, port);
+ printf("Setting delivery mode to PLAYER_DATAMODE_PUSH\n");
// Change the server's data delivery mode.
if (playerc_client_set_replace_rule(client, -1, -1, -1, -1, 0) != 0)
{
Modified: code/player/trunk/utils/playerv/pv_dev_actarray.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_actarray.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_actarray.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -196,8 +196,6 @@
{
double value;
double min, max;
- double ax, ay, bx, by;
- double fx, fd;
int ii;
rtk_fig_t *fig;
Modified: code/player/trunk/utils/playerv/pv_dev_bumper.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_bumper.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_bumper.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -1,4 +1,4 @@
-/*
+/*
* PlayerViewer
* Copyright (C) Andrew Howard 2002
*
@@ -45,11 +45,10 @@
bumper_t *bumper_create(mainwnd_t *mainwnd, opt_t *opt, playerc_client_t
*client,
int index, const char *drivername, int subscribe)
{
- int i;
char label[64];
char section[64];
bumper_t *bumper;
-
+
bumper = malloc(sizeof(bumper_t));
bumper->proxy = playerc_bumper_create(client, index);
bumper->drivername = strdup(drivername);
@@ -78,7 +77,7 @@
if (fig_count <= bumper->fig_count)
return;
bumper->scan_fig =
realloc(bumper->scan_fig,fig_count*sizeof(bumper->scan_fig[0]));
-
+
// Construct figures
for (i = bumper->fig_count; i < fig_count; i++)
bumper->scan_fig[i] = rtk_fig_create(bumper->mainwnd->canvas,
bumper->mainwnd->robot_fig, 1);
@@ -90,7 +89,7 @@
void bumper_destroy(bumper_t *bumper)
{
int i;
-
+
if (bumper->proxy->info.subscribed)
playerc_bumper_unsubscribe(bumper->proxy);
playerc_bumper_destroy(bumper->proxy);
@@ -111,7 +110,7 @@
void bumper_update(bumper_t *bumper)
{
int i;
-
+
// Update the device subscription
if (rtk_menuitem_ischecked(bumper->subscribe_item))
{
@@ -122,7 +121,7 @@
// Get the bumper geometry
if (playerc_bumper_get_geom(bumper->proxy) != 0)
- PRINT_ERR1("get_geom failed : %s", playerc_error_str());
+ PRINT_ERR1("get_geom failed : %s", playerc_error_str());
bumper_allocate_figures(bumper, bumper->proxy->pose_count);
for (i = 0; i < bumper->proxy->pose_count; i++){
@@ -131,7 +130,7 @@
bumper->proxy->poses[i].pose.px, // convert mm to m
bumper->proxy->poses[i].pose.py,
bumper->proxy->poses[i].pose.pyaw); // convert deg to
rad
-
+
}
}
}
@@ -166,7 +165,7 @@
for (i = 0; i< bumper->proxy->bumper_count; i++)
{
- rtk_fig_show(bumper->scan_fig[i], 1);
+ rtk_fig_show(bumper->scan_fig[i], 1);
rtk_fig_clear(bumper->scan_fig[i]);
// Draw in the bumper, diff colour if its active
@@ -191,7 +190,7 @@
else
{
half_angle = (bumper->proxy->poses[i].length)/radius/2.0 - 0.04;
-
rtk_fig_ellipse_arc(bumper->scan_fig[i],-radius,0,0,radius*2,radius*2,-half_angle,half_angle);
+
rtk_fig_ellipse_arc(bumper->scan_fig[i],-radius,0,0,radius*2,radius*2,-half_angle,half_angle);
}
}
}
Modified: code/player/trunk/utils/playerv/pv_dev_camera.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_camera.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_camera.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -148,9 +148,7 @@
// Draw the camera scan
void camera_draw(camera_t *camera)
{
- int i;
char text[64];
- double ox, oy, dx, dy;
int sizex, sizey;
double scalex, scaley;
Modified: code/player/trunk/utils/playerv/pv_dev_dio.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_dio.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_dio.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -121,7 +121,7 @@
void dio_draw(dio_t *dio)
{
int i;
- char ntext[64], str[1024];
+ char str[1024];
uint32_t digin = dio->proxy->digin;
uint32_t count = dio->proxy->count;
Modified: code/player/trunk/utils/playerv/pv_dev_gripper.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_gripper.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_gripper.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -48,7 +48,6 @@
gripper_t *gripper_create(mainwnd_t *mainwnd, opt_t *opt, playerc_client_t
*client,
int index, const char *drivername, int subscribe)
{
- int i;
char label[64];
char section[64];
gripper_t *gripper;
@@ -82,8 +81,6 @@
// Destroy a gripper device
void gripper_destroy(gripper_t *gripper)
{
- int i;
-
if( gripper->grip_fig )
{
rtk_fig_clear(gripper->grip_fig);
@@ -109,7 +106,6 @@
double paddle_center, paddle_length, paddle_width, paddle_pos;
double ibbx, obbx, bby;
double led_dx;
- int i;
// Update the device subscription
if (rtk_menuitem_ischecked(gripper->subscribe_item))
Modified: code/player/trunk/utils/playerv/pv_dev_laser.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_laser.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_laser.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -1,4 +1,4 @@
-/*
+/*
* PlayerViewer
* Copyright (C) Andrew Howard 2002
*
@@ -45,7 +45,7 @@
char label[64];
char section[64];
laser_t *laser;
-
+
laser = malloc(sizeof(laser_t));
laser->proxy = playerc_laser_create(client, index);
@@ -75,7 +75,7 @@
// Construct figures
laser->scan_fig = rtk_fig_create(mainwnd->canvas, mainwnd->robot_fig, 0);
-
+
return laser;
}
@@ -102,7 +102,7 @@
rtk_menu_destroy(laser->menu);
free(laser->drivername);
-
+
free(laser);
}
@@ -141,7 +141,7 @@
// Update the configuration stuff
if (laser->proxy->info.subscribed)
laser_update_config(laser);
-
+
if (laser->proxy->info.subscribed)
{
// Draw in the laser scan if it has been changed.
@@ -165,7 +165,7 @@
int update;
double min, max, range_res, res, scanning_frequency;
unsigned char intensity;
-
+
min = laser->proxy->scan_start;
max = laser->proxy->scan_start +
laser->proxy->scan_count*laser->proxy->scan_res;
range_res = laser->proxy->range_res;
@@ -224,25 +224,23 @@
return;
-}
+}
// Draw the laser scan
void laser_draw(laser_t *laser)
{
int i;
- int style;
double ax, ay, bx, by;
double r, b, res;
- int point_count;
double (*points)[2];
- rtk_fig_show(laser->scan_fig, 1);
+ rtk_fig_show(laser->scan_fig, 1);
rtk_fig_clear(laser->scan_fig);
if (!rtk_menuitem_ischecked(laser->style_item))
{
rtk_fig_color_rgb32(laser->scan_fig, COLOR_LASER_OCC);
-
+
// Draw in the range scan
for (i = 0; i < laser->proxy->scan_count; i++)
{
@@ -261,11 +259,11 @@
else
{
res = laser->proxy->scan_res / 2;
-
+
// Draw in the range scan (empty space)
points = calloc(laser->proxy->scan_count,sizeof(double)*2);
for (i = 0; i < laser->proxy->scan_count; i++)
- {
+ {
r = laser->proxy->scan[i][0];
b = laser->proxy->scan[i][1];
points[i][0] = r * cos(b - res);
@@ -275,7 +273,7 @@
rtk_fig_polygon(laser->scan_fig, 0, 0, 0, laser->proxy->scan_count,
points, 1);
free(points);
points = NULL;
-
+
// Draw in the range scan (occupied space)
rtk_fig_color_rgb32(laser->scan_fig, COLOR_LASER_OCC);
for (i = 0; i < laser->proxy->scan_count; i++)
@@ -288,7 +286,7 @@
by = r * sin(b + res);
rtk_fig_line(laser->scan_fig, ax, ay, bx, by);
}
- }
+ }
// Draw in the intensity scan
for (i = 0; i < laser->proxy->scan_count; i++)
Modified: code/player/trunk/utils/playerv/pv_dev_map.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_map.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_map.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -1,4 +1,4 @@
-/*
+/*
* PlayerViewer
* Copyright (C) Andrew Howard 2002
*
@@ -44,7 +44,7 @@
char label[64];
char section[64];
map_t *map;
-
+
map = malloc(sizeof(map_t));
map->proxy = playerc_map_create(client, index);
map->drivername = strdup(drivername);
@@ -59,10 +59,10 @@
map->continuous_item = rtk_menuitem_create(map->menu, "continuous update",
1);
// Set the initial menu state
rtk_menuitem_check(map->subscribe_item, subscribe);
-
+
// Construct figures
map->fig = rtk_fig_create(mainwnd->canvas, NULL, 1);
-
+
return map;
}
@@ -77,7 +77,7 @@
rtk_fig_destroy(map->fig);
free(map->drivername);
free(map);
-
+
return;
}
@@ -93,7 +93,7 @@
if (playerc_map_subscribe(map->proxy, PLAYER_OPEN_MODE) != 0)
PRINT_ERR1("libplayerc error: %s", playerc_error_str());
// download a map
- if (playerc_map_get_map( map->proxy ) >= 0)
+ if (playerc_map_get_map( map->proxy ) >= 0)
map_draw( map );
}
}
@@ -139,17 +139,16 @@
void map_draw(map_t *map)
{
int x,y;
- char ntext[64], text[1024];
double scale = map->proxy->resolution;
- rtk_fig_show(map->fig, 1);
+ rtk_fig_show(map->fig, 1);
rtk_fig_clear(map->fig);
-
+
puts( "map draw" );
- rtk_fig_color_rgb32(map->fig, 0xFF0000 );
- rtk_fig_rectangle(map->fig,
- 0,0,0,
+ rtk_fig_color_rgb32(map->fig, 0xFF0000 );
+ rtk_fig_rectangle(map->fig,
+ 0,0,0,
map->proxy->width * scale,
map->proxy->height * scale,
0 );
@@ -166,7 +165,7 @@
case -1:
// empty: draw nothing
break;
-
+
case 0:
// unknown: draw grey square
rtk_fig_color_rgb32(map->fig, 0x808080 );
@@ -177,14 +176,14 @@
scale, scale, 1);
break;
- case +1:
+ case +1:
// occupied: draw black square
- rtk_fig_color_rgb32(map->fig, 0x0 );
- rtk_fig_rectangle(map->fig,
- (x - map->proxy->width/2.0) * scale + scale/2.0,
- (y - map->proxy->height/2.0) * scale + scale/2.0,
- 0,
- scale, scale, 1);
+ rtk_fig_color_rgb32(map->fig, 0x0 );
+ rtk_fig_rectangle(map->fig,
+ (x - map->proxy->width/2.0) * scale + scale/2.0,
+ (y - map->proxy->height/2.0) * scale + scale/2.0,
+ 0,
+ scale, scale, 1);
break;
default:
Modified: code/player/trunk/utils/playerv/pv_dev_sonar.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_sonar.c 2009-06-07 07:21:45 UTC
(rev 7806)
+++ code/player/trunk/utils/playerv/pv_dev_sonar.c 2009-06-07 07:44:40 UTC
(rev 7807)
@@ -1,4 +1,4 @@
-/*
+/*
* PlayerViewer
* Copyright (C) Andrew Howard 2002
*
@@ -47,11 +47,10 @@
sonar_t *sonar_create(mainwnd_t *mainwnd, opt_t *opt, playerc_client_t *client,
int index, const char *drivername, int subscribe)
{
- int i;
char label[64];
char section[64];
sonar_t *sonar;
-
+
sonar = malloc(sizeof(sonar_t));
sonar->proxy = playerc_sonar_create(client, index);
sonar->drivername = strdup(drivername);
@@ -81,7 +80,7 @@
if (fig_count <= sonar->fig_count)
return;
sonar->scan_fig =
realloc(sonar->scan_fig,fig_count*sizeof(sonar->scan_fig[0]));
-
+
// Construct figures
for (i = sonar->fig_count; i < fig_count; i++)
sonar->scan_fig[i] = rtk_fig_create(sonar->mainwnd->canvas,
sonar->mainwnd->robot_fig, 1);
@@ -93,7 +92,7 @@
void sonar_destroy(sonar_t *sonar)
{
int i;
-
+
if (sonar->proxy->info.subscribed)
playerc_sonar_unsubscribe(sonar->proxy);
playerc_sonar_destroy(sonar->proxy);
@@ -112,8 +111,6 @@
// Update a sonar device
void sonar_update(sonar_t *sonar)
{
- int i;
-
// Update the device subscription
if (rtk_menuitem_ischecked(sonar->subscribe_item))
{
@@ -124,7 +121,7 @@
// Get the sonar geometry
if (playerc_sonar_get_geom(sonar->proxy) != 0)
- PRINT_ERR1("get_geom failed : %s", playerc_error_str());
+ PRINT_ERR1("get_geom failed : %s", playerc_error_str());
sonar_update_geom(sonar);
}
@@ -144,7 +141,7 @@
sonar->proxy->info.freshgeom = 0;
sonar_update_geom(sonar);
}
-
+
// Draw in the sonar scan if it has been changed.
if (sonar->proxy->info.datatime != sonar->datatime)
sonar_draw(sonar);
@@ -180,7 +177,7 @@
for (i = 0; i < sonar->proxy->scan_count; i++)
{
- rtk_fig_show(sonar->scan_fig[i], 1);
+ rtk_fig_show(sonar->scan_fig[i], 1);
rtk_fig_clear(sonar->scan_fig[i]);
// Draw in the sonar itself
@@ -191,7 +188,7 @@
rtk_fig_color_rgb32(sonar->scan_fig[i], COLOR_SONAR_SCAN);
dr = sonar->proxy->scan[i];
da = 20 * M_PI / 180 / 2;
-
+
//rtk_fig_line(sonar->scan_fig[i], 0, 0, dr, 0);
//rtk_fig_line(sonar->scan_fig[i], dr, -dr * da/2, dr, +dr * da/2);
points[0][0] = 0;
This was sent by the SourceForge.net collaborative development platform, the
world's largest Open Source development site.
------------------------------------------------------------------------------
OpenSolaris 2009.06 is a cutting edge operating system for enterprises
looking to deploy the next generation of Solaris that includes the latest
innovations from Sun and the OpenSource community. Download a copy and
enjoy capabilities such as Networking, Storage and Virtualization.
Go to: http://p.sf.net/sfu/opensolaris-get
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit