Update of /cvsroot/playerstage/code/player/server/drivers/mixed/rflex
In directory
sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv10946/server/drivers/mixed/rflex
Modified Files:
.cvsignore rflex.cc rflex.h rflex_configs.h
Log Message:
applied Toby's patch to replace fixed-size arrays
Index: .cvsignore
===================================================================
RCS file:
/cvsroot/playerstage/code/player/server/drivers/mixed/rflex/.cvsignore,v
retrieving revision 1.2
retrieving revision 1.3
diff -C2 -d -r1.2 -r1.3
*** .cvsignore 17 Sep 2007 02:18:58 -0000 1.2
--- .cvsignore 1 Nov 2007 22:16:21 -0000 1.3
***************
*** 4,5 ****
--- 4,7 ----
*.la
*.a
+ .libs
+ *.lo
Index: rflex.cc
===================================================================
RCS file: /cvsroot/playerstage/code/player/server/drivers/mixed/rflex/rflex.cc,v
retrieving revision 1.39
retrieving revision 1.40
diff -C2 -d -r1.39 -r1.40
*** rflex.cc 23 Aug 2007 19:58:46 -0000 1.39
--- rflex.cc 1 Nov 2007 22:16:21 -0000 1.40
***************
*** 315,318 ****
--- 315,319 ----
#include <libplayercore/playercore.h>
+ #include <libplayerxdr/playerxdr.h>
extern PlayerTime* GlobalTime;
***************
*** 395,398 ****
--- 396,400 ----
Lock();
geom.poses_count = rflex_configs.sonar_1st_bank_end;
+ geom.poses = new player_pose3d_t[geom.poses_count];
for (int i = 0; i < rflex_configs.sonar_1st_bank_end; i++)
{
***************
*** 401,404 ****
--- 403,407 ----
Unlock();
Publish(sonar_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, hdr->subtype,
&geom,sizeof(geom));
+ delete [] geom.poses;
return 0;
}
***************
*** 411,414 ****
--- 414,418 ----
Lock();
geom.poses_count = (rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start);
+ geom.poses = new player_pose3d_t[geom.poses_count];
for (int i = 0; i < rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start; i++)
{
***************
*** 417,420 ****
--- 421,425 ----
Unlock();
Publish(sonar_id_2, resp_queue, PLAYER_MSGTYPE_RESP_ACK, hdr->subtype,
&geom,sizeof(geom));
+ delete [] geom.poses;
return 0;
}
***************
*** 427,430 ****
--- 432,436 ----
Lock();
geom.bumper_def_count = rflex_configs.bumper_count;
+ geom.bumper_def = new player_bumper_define_t[geom.bumper_def_count];
for (int i = 0; i < rflex_configs.bumper_count; i++)
{
***************
*** 433,436 ****
--- 439,443 ----
Unlock();
Publish(bumper_id, resp_queue, PLAYER_MSGTYPE_RESP_ACK, hdr->subtype,
&geom,sizeof(geom));
+ delete [] geom.bumper_def;
return 0;
}
***************
*** 764,768 ****
for(int i=0; i < rflex_configs.ir_bank_count; ++i)
RunningTotal += (rflex_configs.ir_count[i]=(int)
cf->ReadTupleFloat(section, "rflex_banks",i,0));
!
// posecount is actually unnecasary, but for consistancy will juse use it
for error checking :)
if (RunningTotal != rflex_configs.ir_poses.poses_count)
--- 771,775 ----
for(int i=0; i < rflex_configs.ir_bank_count; ++i)
RunningTotal += (rflex_configs.ir_count[i]=(int)
cf->ReadTupleFloat(section, "rflex_banks",i,0));
! rflex_configs.ir_total_count = RunningTotal;
// posecount is actually unnecasary, but for consistancy will juse use it
for error checking :)
if (RunningTotal != rflex_configs.ir_poses.poses_count)
***************
*** 823,826 ****
--- 830,837 ----
}
+ RFLEX::~RFLEX()
+ {
+ }
+
int RFLEX::Setup(){
/* now spawn reading thread */
***************
*** 1104,1107 ****
--- 1115,1119 ----
Lock();
geom.poses_count = rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start;
+ geom.poses = new player_pose3d_t[geom.poses_count];
for (i = 0; i < rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start; i++)
{
***************
*** 1115,1118 ****
--- 1127,1131 ----
Publish(this->sonar_id_2, PLAYER_MSGTYPE_DATA,
PLAYER_SONAR_DATA_GEOM,
(unsigned char*)&geom, sizeof(player_sonar_geom_t), NULL);
+ delete [] geom.poses;
}
LastYaw = rflex_data.position.pos.pa;
***************
*** 1152,1157 ****
NULL);
}
- ret=pthread_setcancelstate(oldstate,NULL);
Lock();
if (!ThreadAlive)
--- 1165,1179 ----
NULL);
}
+ ret=pthread_setcancelstate(oldstate,NULL);
+ player_position2d_data_t_cleanup(&rflex_data.position);
+ player_sonar_data_t_cleanup(&rflex_data.sonar);
+ player_sonar_data_t_cleanup(&rflex_data.sonar2);
+ player_gripper_data_t_cleanup(&rflex_data.gripper);
+ player_power_data_t_cleanup(&rflex_data.power);
+ player_bumper_data_t_cleanup(&rflex_data.bumper);
+ player_dio_data_t_cleanup(&rflex_data.dio);
+ player_aio_data_t_cleanup(&rflex_data.aio);
+ player_ir_data_t_cleanup(&rflex_data.ir);
Lock();
if (!ThreadAlive)
***************
*** 1208,1221 ****
{
! int arb_ranges[PLAYER_SONAR_MAX_SAMPLES];
! char abumper_ranges[PLAYER_BUMPER_MAX_SAMPLES];
! unsigned char air_ranges[PLAYER_IR_MAX_SAMPLES];
!
! // changed these variable-size array declarations to the
! // bigger-than-necessary ones above, because older versions of gcc don't
! // support variable-size arrays.
! // int arb_ranges[rflex_configs.num_sonars];
! // char abumper_ranges[rflex_configs.bumper_count];
! // unsigned char air_ranges[rflex_configs.ir_poses.pose_count];
static int initialized = 0;
--- 1230,1236 ----
{
! int *arb_ranges = new int[rflex_configs.num_sonars];
! char *abumper_ranges = new char[rflex_configs.bumper_count];
! uint8_t *air_ranges = new uint8_t[rflex_configs.ir_total_count];
static int initialized = 0;
***************
*** 1284,1292 ****
arb_ranges);
// pthread_testcancel();
! d->sonar.ranges_count=(rflex_configs.sonar_1st_bank_end);
for (i = 0; i < rflex_configs.sonar_1st_bank_end; i++){
d->sonar.ranges[i] = ARB2M_RANGE_CONV(arb_ranges[i]);
}
! d->sonar2.ranges_count=(rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start);
for (i = 0; i < rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start; i++){
d->sonar2.ranges[i] =
ARB2M_RANGE_CONV(arb_ranges[rflex_configs.sonar_2nd_bank_start+i]);
--- 1299,1317 ----
arb_ranges);
// pthread_testcancel();
! if (d->sonar.ranges_count!=rflex_configs.sonar_1st_bank_end)
! {
! d->sonar.ranges_count=rflex_configs.sonar_1st_bank_end;
! delete [] d->sonar.ranges;
! d->sonar.ranges = new float[d->sonar.ranges_count];
! }
for (i = 0; i < rflex_configs.sonar_1st_bank_end; i++){
d->sonar.ranges[i] = ARB2M_RANGE_CONV(arb_ranges[i]);
}
! if (d->sonar2.ranges_count!=(rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start))
! {
! d->sonar2.ranges_count=(rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start);
! delete [] d->sonar2.ranges;
! d->sonar2.ranges = new float[d->sonar2.ranges_count];
! }
for (i = 0; i < rflex_configs.num_sonars -
rflex_configs.sonar_2nd_bank_start; i++){
d->sonar2.ranges[i] =
ARB2M_RANGE_CONV(arb_ranges[rflex_configs.sonar_2nd_bank_start+i]);
***************
*** 1305,1309 ****
d->bumper.bumpers_count=(a_num_bumpers);
! memcpy(d->bumper.bumpers,abumper_ranges,a_num_bumpers);
}
--- 1330,1334 ----
d->bumper.bumpers_count=(a_num_bumpers);
! d->bumper.bumpers = (uint8_t*)abumper_ranges;
}
***************
*** 1318,1322 ****
// pthread_testcancel();
! d->ir.ranges_count = (a_num_ir);
for (int i = 0; i < a_num_ir; ++i)
{
--- 1343,1355 ----
// pthread_testcancel();
! if (d->ir.ranges_count != a_num_ir)
! {
! d->ir.ranges_count = a_num_ir;
! d->ir.voltages_count = a_num_ir;
! delete [] d->ir.ranges;
! delete [] d->ir.voltages;
! d->ir.ranges = new float [a_num_ir];
! d->ir.voltages = new float [a_num_ir];
! }
for (int i = 0; i < a_num_ir; ++i)
{
Index: rflex.h
===================================================================
RCS file: /cvsroot/playerstage/code/player/server/drivers/mixed/rflex/rflex.h,v
retrieving revision 1.18
retrieving revision 1.19
diff -C2 -d -r1.18 -r1.19
*** rflex.h 23 Aug 2007 19:58:46 -0000 1.18
--- rflex.h 1 Nov 2007 22:16:21 -0000 1.19
***************
*** 131,134 ****
--- 131,135 ----
public:
RFLEX(ConfigFile* cf, int section);
+ ~RFLEX();
/* the main thread */
Index: rflex_configs.h
===================================================================
RCS file:
/cvsroot/playerstage/code/player/server/drivers/mixed/rflex/rflex_configs.h,v
retrieving revision 1.14
retrieving revision 1.15
diff -C2 -d -r1.14 -r1.15
*** rflex_configs.h 9 Jul 2007 17:18:01 -0000 1.14
--- rflex_configs.h 1 Nov 2007 22:16:21 -0000 1.15
***************
*** 96,99 ****
--- 96,100 ----
int ir_base_bank;
int ir_bank_count;
+ int ir_total_count;
int * ir_count;
double * ir_a;
-------------------------------------------------------------------------
This SF.net email is sponsored by: Splunk Inc.
Still grepping through log files to find problems? Stop.
Now Search log events and configuration files using AJAX and a browser.
Download your FREE copy of Splunk now >> http://get.splunk.com/
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit