Update of /cvsroot/playerstage/code/stage/libstageplugin
In directory sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv21970/libstageplugin
Modified Files:
Tag: opengl
Makefile.am p_driver.cc p_driver.h p_laser.cc p_position.cc
p_simulation.cc p_sonar.cc stg_time.cc
Log Message:
libstageplugin basic working for P-2.1
Index: p_sonar.cc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/p_sonar.cc,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** p_sonar.cc 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- p_sonar.cc 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 65,75 ****
{
// limit the number of samples to Player's maximum
! if( sensor_count > PLAYER_SONAR_MAX_SAMPLES )
! sensor_count = PLAYER_SONAR_MAX_SAMPLES;
//if( son->power_on ) // set with a sonar config
{
sonar.ranges_count = sensor_count;
!
for( unsigned int i=0; i<sensor_count; i++ )
sonar.ranges[i] = mod->sensors[i].range;
--- 65,76 ----
{
// limit the number of samples to Player's maximum
! //if( sensor_count > PLAYER_SONAR_MAX_SAMPLES )
! //sensor_count = PLAYER_SONAR_MAX_SAMPLES;
//if( son->power_on ) // set with a sonar config
{
sonar.ranges_count = sensor_count;
! sonar.ranges = new float[sensor_count];
!
for( unsigned int i=0; i<sensor_count; i++ )
sonar.ranges[i] = mod->sensors[i].range;
***************
*** 77,88 ****
}
! this->driver->Publish( this->addr, NULL,
PLAYER_MSGTYPE_DATA,
PLAYER_SONAR_DATA_RANGES,
&sonar, sizeof(sonar), NULL);
}
! int InterfaceSonar::ProcessMessage( MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data )
--- 78,92 ----
}
! this->driver->Publish( this->addr,
PLAYER_MSGTYPE_DATA,
PLAYER_SONAR_DATA_RANGES,
&sonar, sizeof(sonar), NULL);
+
+ if( sonar.ranges )
+ delete[] sonar.ranges;
}
! int InterfaceSonar::ProcessMessage( QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data )
***************
*** 98,103 ****
// limit the number of samples to Player's maximum
! if( rcount > PLAYER_SONAR_MAX_SAMPLES )
! rcount = PLAYER_SONAR_MAX_SAMPLES;
// convert the ranger data into Player-format sonar poses
--- 102,107 ----
// limit the number of samples to Player's maximum
! //if( rcount > PLAYER_SONAR_MAX_SAMPLES )
! //rcount = PLAYER_SONAR_MAX_SAMPLES;
// convert the ranger data into Player-format sonar poses
***************
*** 106,110 ****
pgeom.poses_count = rcount;
!
for( unsigned int i=0; i<rcount; i++ )
{
--- 110,115 ----
pgeom.poses_count = rcount;
! pgeom.poses = new player_pose3d_t[rcount];
!
for( unsigned int i=0; i<rcount; i++ )
{
***************
*** 119,123 ****
PLAYER_SONAR_REQ_GET_GEOM,
(void*)&pgeom, sizeof(pgeom), NULL );
!
return 0; // ok
}
--- 124,129 ----
PLAYER_SONAR_REQ_GET_GEOM,
(void*)&pgeom, sizeof(pgeom), NULL );
!
! delete[] pgeom.poses;
return 0; // ok
}
Index: p_driver.h
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/p_driver.h,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** p_driver.h 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- p_driver.h 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 8,12 ****
#include <libplayercore/playercore.h>
! #include "model.hh"
#include "stg_time.h"
--- 8,12 ----
#include <libplayercore/playercore.h>
! #include "../libstage/stage.hh"
#include "stg_time.h"
***************
*** 28,32 ****
virtual int Setup();
virtual int Shutdown();
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr * hdr,
void * data);
--- 28,32 ----
virtual int Setup();
virtual int Shutdown();
! virtual int ProcessMessage(QueuePointer &resp_queue,
player_msghdr * hdr,
void * data);
***************
*** 37,43 ****
/// check for new commands and configs
virtual void Update();
!
/// all player devices share the same Stage world (for now)
! static stg_world_t* world;
/// find the device record with this Player id
--- 37,43 ----
/// check for new commands and configs
virtual void Update();
!
/// all player devices share the same Stage world (for now)
! static StgWorld* world;
/// find the device record with this Player id
***************
*** 71,75 ****
StgDriver* driver; // the driver instance that created this device
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data) { return(-1); } // empty implementation
--- 71,75 ----
StgDriver* driver; // the driver instance that created this device
! virtual int ProcessMessage(QueuePointer &resp_queue,
player_msghdr_t* hdr,
void* data) { return(-1); } // empty implementation
***************
*** 86,90 ****
InterfaceSimulation( player_devaddr_t addr, StgDriver* driver,ConfigFile*
cf, int section );
virtual ~InterfaceSimulation( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 86,90 ----
InterfaceSimulation( player_devaddr_t addr, StgDriver* driver,ConfigFile*
cf, int section );
virtual ~InterfaceSimulation( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 92,96 ****
// base class for all interfaces that are associated with a model
! class InterfaceModel : public Interface
{
public:
--- 92,98 ----
// base class for all interfaces that are associated with a model
! class InterfaceModel
!
! : public Interface
{
public:
***************
*** 116,120 ****
virtual ~InterfacePosition( void ){ /* TODO: clean up*/ };
virtual void Publish( void );
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 118,122 ----
virtual ~InterfacePosition( void ){ /* TODO: clean up*/ };
virtual void Publish( void );
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 126,130 ****
InterfaceGripper( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceGripper( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 128,132 ----
InterfaceGripper( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceGripper( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 137,141 ****
InterfaceWifi( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceWifi( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 139,143 ----
InterfaceWifi( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceWifi( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 148,152 ****
InterfaceSpeech( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceSpeech( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 150,154 ----
InterfaceSpeech( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceSpeech( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 161,165 ****
InterfaceLaser( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceLaser( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 163,167 ----
InterfaceLaser( player_devaddr_t addr, StgDriver* driver, ConfigFile* cf,
int section );
virtual ~InterfaceLaser( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 173,177 ****
virtual ~InterfacePower( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 175,179 ----
virtual ~InterfacePower( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
***************
*** 187,191 ****
virtual void Publish( void );
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 189,193 ----
virtual void Publish( void );
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 199,203 ****
virtual ~InterfaceBlobfinder( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 201,205 ----
virtual ~InterfaceBlobfinder( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
***************
*** 211,215 ****
virtual ~InterfacePtz( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 213,217 ----
virtual ~InterfacePtz( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
***************
*** 223,227 ****
virtual ~InterfaceSonar( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 225,229 ----
virtual ~InterfaceSonar( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
***************
*** 236,240 ****
virtual ~InterfaceBumper( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 238,242 ----
virtual ~InterfaceBumper( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
***************
*** 253,257 ****
virtual void Publish( void );
! virtual int ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data);
--- 255,259 ----
virtual void Publish( void );
! virtual int ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data);
***************
*** 264,268 ****
virtual ~InterfaceMap( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 266,270 ----
virtual ~InterfaceMap( void ){ /* TODO: clean up*/ };
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
***************
*** 271,300 ****
// called by ProcessMessage to handle individual messages
! int HandleMsgReqInfo( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
! int HandleMsgReqData( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
};
- /* class InterfaceGraphics2d : public InterfaceModelModel */
- /* { */
- /* public: */
- /* InterfaceGraphics2d( player_devaddr_t addr, StgDriver* driver,
ConfigFile* cf, int section ); */
- /* virtual ~InterfaceGraphics2d( void ); */
-
- /* virtual int ProcessMessage( MessageQueue* resp_queue, */
- /* player_msghdr * hdr, */
- /* void * data ); */
- /* private: */
- /* stg_rtk_fig_t* fig; // a figure we can draw in */
-
- /* GList* drawlist; // list of drawing commands */
-
- /* // clear the display */
- /* void Clear( void ); */
- /* }; */
-
class InterfaceGraphics3d : public InterfaceModel
{
--- 273,284 ----
// called by ProcessMessage to handle individual messages
! int HandleMsgReqInfo( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
! int HandleMsgReqData( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
};
class InterfaceGraphics3d : public InterfaceModel
{
***************
*** 303,307 ****
virtual ~InterfaceGraphics3d( void );
! virtual int ProcessMessage( MessageQueue* resp_queue,
player_msghdr * hdr,
void * data );
--- 287,291 ----
virtual ~InterfaceGraphics3d( void );
! virtual int ProcessMessage( QueuePointer & resp_queue,
player_msghdr * hdr,
void * data );
Index: p_position.cc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/p_position.cc,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** p_position.cc 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- p_position.cc 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 57,61 ****
}
! int InterfacePosition::ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data)
--- 57,61 ----
}
! int InterfacePosition::ProcessMessage(QueuePointer &resp_queue,
player_msghdr_t* hdr,
void* data)
***************
*** 314,318 ****
// publish this data
! this->driver->Publish( this->addr, NULL,
PLAYER_MSGTYPE_DATA, PLAYER_POSITION2D_DATA_STATE,
(void*)&ppd, sizeof(ppd), NULL);
--- 314,318 ----
// publish this data
! this->driver->Publish( this->addr,
PLAYER_MSGTYPE_DATA, PLAYER_POSITION2D_DATA_STATE,
(void*)&ppd, sizeof(ppd), NULL);
Index: p_laser.cc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/p_laser.cc,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** p_laser.cc 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- p_laser.cc 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 52,60 ****
void InterfaceLaser::Publish( void )
{
! player_laser_data_t pdata;
! memset( &pdata, 0, sizeof(pdata) );
StgModelLaser* mod = (StgModelLaser*)this->mod;
pdata.min_angle = -mod->fov/2.0;
pdata.max_angle = +mod->fov/2.0;
--- 52,64 ----
void InterfaceLaser::Publish( void )
{
!
StgModelLaser* mod = (StgModelLaser*)this->mod;
+ if( mod->samples == NULL )
+ return;
+ player_laser_data_t pdata;
+ memset( &pdata, 0, sizeof(pdata) );
+
pdata.min_angle = -mod->fov/2.0;
pdata.max_angle = +mod->fov/2.0;
***************
*** 64,71 ****
pdata.id = this->scan_id++;
for( int i=0; i<mod->sample_count; i++ )
{
//printf( "range %d %d\n", i, samples[i].range);
-
pdata.ranges[i] = mod->samples[i].range;
pdata.intensity[i] = (uint8_t)mod->samples[i].reflectance;
--- 68,77 ----
pdata.id = this->scan_id++;
+ pdata.ranges = new float[pdata.ranges_count];
+ pdata.intensity = new uint8_t[pdata.ranges_count];
+
for( int i=0; i<mod->sample_count; i++ )
{
//printf( "range %d %d\n", i, samples[i].range);
pdata.ranges[i] = mod->samples[i].range;
pdata.intensity[i] = (uint8_t)mod->samples[i].reflectance;
***************
*** 73,83 ****
// Write laser data
! this->driver->Publish(this->addr, NULL,
PLAYER_MSGTYPE_DATA,
PLAYER_LASER_DATA_SCAN,
(void*)&pdata, sizeof(pdata), NULL);
}
! int InterfaceLaser::ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data)
--- 79,92 ----
// Write laser data
! this->driver->Publish(this->addr,
PLAYER_MSGTYPE_DATA,
PLAYER_LASER_DATA_SCAN,
(void*)&pdata, sizeof(pdata), NULL);
+
+ delete [] pdata.ranges;
+ delete [] pdata.intensity;
}
! int InterfaceLaser::ProcessMessage(QueuePointer & resp_queue,
player_msghdr_t* hdr,
void* data)
Index: p_driver.cc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/p_driver.cc,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** p_driver.cc 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- p_driver.cc 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 170,174 ****
// init static vars
! stg_world_t* StgDriver::world = NULL;
int update_request = 0;
--- 170,174 ----
// init static vars
! StgWorld* StgDriver::world = NULL;
int update_request = 0;
***************
*** 186,189 ****
--- 186,190 ----
Driver* StgDriver_Init(ConfigFile* cf, int section)
{
+ puts( "HELLO WORLD" );
// Create and return a new instance of this driver
return ((Driver*) (new StgDriver(cf, section)));
***************
*** 210,273 ****
puts(" Stage driver plugin init");
StgDriver_Register(table);
- //ZooDriver_Register(table);
return(0);
}
! // find a model to attach to a Player interface
! StgModel* model_match( StgModel* mod,
! player_devaddr_t *addr,
! char* typestr,
! GPtrArray* devices )
! {
! //printf( "model_match %s[%s] for [%s]\n",
! // mod->Token(), mod->TypeStr(), typestr );
! if( strcmp( mod->TypeStr(), typestr ) == 0 )
! return mod;
! //printf( "searching children\n" );
! // else try the children
! StgModel* match=NULL;
! // for each model in the child list
! GList* it;
! int i=0;
! for( it=mod->Children(); it; it=it->next )
! {
! // recurse
! match =
! model_match( (StgModel*)it->data,
! addr, typestr, devices );
! if( match )
! {
! // if mod appears in devices already, it can not be used now
! //printf( "[inspecting %d devices used already]", devices->len );
! for( int i=0; i<(int)devices->len; i++ )
! {
! InterfaceModel* interface =
! (InterfaceModel*)g_ptr_array_index( devices, i );
! //printf( "comparing %p and %p (%d.%d.%d)\n", mod, record->mod,
! // record->id.port, record->id.code, record->id.index );
! // if we have this type of interface on this model already, it's
no-go.
! if( match == interface->mod && interface->addr.interf ==
addr->interf )
! {
! //printf( "[MODEL ALREADY HAS AN INTERFACE]" );
! //return NULL;
! match = NULL;
! }
! }
! // if we found a match, we're done searching
! //return match;
! if( match ) return match;
! }
! i++;
! }
! return NULL;
! }
--- 211,273 ----
puts(" Stage driver plugin init");
StgDriver_Register(table);
return(0);
}
! // // find a model to attach to a Player interface
! // StgModel* model_match( StgModel* mod,
! // player_devaddr_t *addr,
! // char* typestr,
! // GPtrArray* devices )
! // {
! // //printf( "model_match %s[%s] for [%s]\n",
! // // mod->Token(), mod->TypeStr(), typestr );
! // // if( strcmp( mod->TypeStr(), typestr ) == 0 )
! // // return mod;
! // // //printf( "searching children\n" );
! // // // else try the children
! // // StgModel* match=NULL;
! // // // for each model in the child list
! // // GList* it;
! // // int i=0;
! // // for( it=mod->Children(); it; it=it->next )
! // // {
! // // // recurse
! // // match =
! // // model_match( (StgModel*)it->data,
! // // addr, typestr, devices );
! // // if( match )
! // // {
! // // // if mod appears in devices already, it can not be used now
! // // //printf( "[inspecting %d devices used already]",
devices->len );
! // // for( int i=0; i<(int)devices->len; i++ )
! // // {
! // // InterfaceModel* interface =
! // // (InterfaceModel*)g_ptr_array_index( devices, i );
! // // //printf( "comparing %p and %p (%d.%d.%d)\n", mod,
record->mod,
! // // // record->id.port, record->id.code,
record->id.index );
! // // // if we have this type of interface on this model
already, it's no-go.
! // // if( match == interface->mod && interface->addr.interf ==
addr->interf )
! // // {
! // // //printf( "[MODEL ALREADY HAS AN INTERFACE]" );
! // // //return NULL;
! // // match = NULL;
! // // }
! // // }
! // // // if we found a match, we're done searching
! // // //return match;
! // // if( match ) return match;
! // // }
! // // i++;
! // // }
! // return NULL;
! // }
***************
*** 474,479 ****
// basename, typestr );
! StgModel* base_model =
! stg_world_model_name_lookup( StgDriver::world, basename );
if( base_model == NULL )
--- 474,478 ----
// basename, typestr );
! StgModel* base_model = world->GetModel( basename );
if( base_model == NULL )
***************
*** 487,496 ****
return base_model;
! //printf( "found base model %s\n", base_model->Token() );
// we find the first model in the tree that is the right
// type (i.e. has the right initialization function) and has not
// been used before
! return( model_match( base_model, addr, typestr, this->devices ) );
}
--- 486,496 ----
return base_model;
! printf( "found base model %s\n", base_model->Token() );
// we find the first model in the tree that is the right
// type (i.e. has the right initialization function) and has not
// been used before
! //return( model_match( base_model, addr, typestr, this->devices ) );
! return( base_model->GetUnsubcribedModelOfType( typestr ) );
}
***************
*** 595,599 ****
// called periodically by player.
int
! StgDriver::ProcessMessage(MessageQueue* resp_queue,
player_msghdr * hdr,
void * data)
--- 595,599 ----
// called periodically by player.
int
! StgDriver::ProcessMessage(QueuePointer &resp_queue,
player_msghdr * hdr,
void * data)
***************
*** 629,634 ****
{
case PLAYER_SIMULATION_CODE:
! if( stg_world_update( this->world, FALSE ) )
! player_quit = TRUE; // set Player's global quit flag
break;
--- 629,635 ----
{
case PLAYER_SIMULATION_CODE:
! //if( stg_world_update( this->world, FALSE ) )
! world->RealTimeUpdate();
! //player_quit = TRUE; // set Player's global quit flag
break;
Index: Makefile.am
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/Makefile.am,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** Makefile.am 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- Makefile.am 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 1,14 ****
!
! # Automake script to build Stage's Makefile
#
! # RTV 20021026
# $Id$
SUBDIRS =
- CC=g++
-
# system-wide compile flags - target-specific flags are added to each target
below
! AM_CPPFLAGS = -Wall -I. -I../libstage -I$(top_srcdir)/replace @GUI_CFLAGS@
# if Player is present, build the plugin and the test program
--- 1,11 ----
! # Automake script to build Libstageplugin's Makefile
#
! # RTV 20071126
# $Id$
SUBDIRS =
# system-wide compile flags - target-specific flags are added to each target
below
! AM_CPPFLAGS = -Wall -I. -I../libstage -I$(top_srcdir)/replace
@PIXBUF_CFLAGS@ @FLTK_CFLAGS@
# if Player is present, build the plugin and the test program
***************
*** 21,25 ****
p_driver.cc \
p_driver.h \
- p_graphics3d.cc \
p_laser.cc \
p_position.cc \
--- 18,21 ----
***************
*** 29,32 ****
--- 25,33 ----
stg_time.h
+ # TODO
+ # p_gripper.cc
+ # p_power.cc
+ # p_graphics2d.cc
+ # p_graphics3d.cc
# p_bumper.cc
# p_fiducial.cc
***************
*** 37,70 ****
# p_map.cc
# p_blobfinder.cc
- # zoo_driver.h
- # zoo.h
- # zoo_controller.h
- # zoo_referee.h
- # zoo_species.h
-
- # TODO
- # p_gripper.cc # slightly broken by PADI-2.1 changes
- # p_power.cc
- # p_graphics2d.cc
-
- # TODO fix these and move them to a separate tree?
- #zoo.c
- #zoo_driver.cc
- #zoo_species.cc
- #zoo_controller.cc
- #zoo_referee.cc
libstageplugin_la_CPPFLAGS = $(AM_CPPFLAGS) @PLAYER_CFLAGS@
! libstageplugin_la_LDFLAGS = -version-info 1:0:0 -rpath $(libdir)
! libstageplugin_la_LIBADD = libstage.la @PLAYER_LIBS@ @GUI_LIBS@
# build a Player plugin from libstage plus Player driver hooks.
#libglutgraphics_la_SOURCES = glutgraphics.cc
-
#libglutgraphics_la_CPPFLAGS = $(AM_CPPFLAGS) @PLAYER_CFLAGS@
#libglutgraphics_la_LDFLAGS = -version-info 1:0:0 -rpath $(libdir) -framework
GLUT
#libglutgraphics_la_LIBADD = libstage.la @PLAYER_LIBS@
-
# build a player client that tests the plugin
#ptest_DEPENDENCIES =
--- 38,52 ----
# p_map.cc
# p_blobfinder.cc
libstageplugin_la_CPPFLAGS = $(AM_CPPFLAGS) @PLAYER_CFLAGS@
! libstageplugin_la_LDFLAGS = -version-info 1:0:0 -rpath $(libdir)
-L../libstage
! libstageplugin_la_LIBADD = ../libstage/libstage.la @PLAYER_LIBS@
# build a Player plugin from libstage plus Player driver hooks.
#libglutgraphics_la_SOURCES = glutgraphics.cc
#libglutgraphics_la_CPPFLAGS = $(AM_CPPFLAGS) @PLAYER_CFLAGS@
#libglutgraphics_la_LDFLAGS = -version-info 1:0:0 -rpath $(libdir) -framework
GLUT
#libglutgraphics_la_LIBADD = libstage.la @PLAYER_LIBS@
# build a player client that tests the plugin
#ptest_DEPENDENCIES =
Index: p_simulation.cc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/p_simulation.cc,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** p_simulation.cc 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- p_simulation.cc 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 49,53 ****
--- 49,55 ----
#define DEBUG
+ #include <libplayercore/globals.h> // for player_argc & player_argv
#include "p_driver.h"
+ #include <libgen.h> // for dirname(3)
// these are Player globals
***************
*** 60,67 ****
////////////////////////////////////////////////////////////////////////////////////
- // player's cmdline args
- //extern int global_argc;
- //extern char** global_argv;
-
//
// SIMULATION INTERFACE
--- 62,65 ----
***************
*** 83,86 ****
--- 81,86 ----
// stg_init( argc, argv );
+ StgWorld::Init( &player_argc, &player_argv );
+
const char* worldfile_name = cf->ReadString(section, "worldfile", NULL );
***************
*** 117,131 ****
// worldfile
! StgDriver::world = stg_world_create_from_file( 0, fullname );
assert(StgDriver::world);
//printf( " done.\n" );
// poke the P/S name into the window title bar
! if( StgDriver::world && StgDriver::world->win )
! {
! char txt[128];
! snprintf( txt, 128, "Player/Stage: %s", StgDriver::world->token );
! stg_world_set_title(StgDriver::world, txt );
! }
// steal the global clock - a bit aggressive, but a simple approach
--- 117,133 ----
// worldfile
! StgDriver::world = new StgWorldGui( 700,700, "Player/Stage" );
assert(StgDriver::world);
+
+ StgDriver::world->Load( fullname );
//printf( " done.\n" );
// poke the P/S name into the window title bar
! // if( StgDriver::world )
! // {
! // char txt[128];
! // snprintf( txt, 128, "Player/Stage: %s", StgDriver::world->token );
! // StgDriverstg_world_set_title(StgDriver::world, txt );
! // }
// steal the global clock - a bit aggressive, but a simple approach
***************
*** 151,155 ****
}
! int InterfaceSimulation::ProcessMessage(MessageQueue* resp_queue,
player_msghdr_t* hdr,
void* data)
--- 153,157 ----
}
! int InterfaceSimulation::ProcessMessage(QueuePointer &resp_queue,
player_msghdr_t* hdr,
void* data)
***************
*** 170,175 ****
// look up the named model
! StgModel* mod =
! stg_world_model_name_lookup( StgDriver::world, req->name );
if( mod )
--- 172,176 ----
// look up the named model
! StgModel* mod = StgDriver::world->GetModel( req->name );
if( mod )
***************
*** 202,206 ****
// look up the named model
StgModel* mod =
! stg_world_model_name_lookup( StgDriver::world, req->name );
if( mod )
--- 203,208 ----
// look up the named model
StgModel* mod =
! //stg_world_model_name_lookup( StgDriver::world, req->name );
! StgDriver::world->GetModel( req->name );
if( mod )
***************
*** 233,237 ****
// look up the named model
StgModel* mod =
! stg_world_model_name_lookup( StgDriver::world, req->name );
if( mod )
--- 235,240 ----
// look up the named model
StgModel* mod =
! //stg_world_model_name_lookup( StgDriver::world, req->name );
! StgDriver::world->GetModel( req->name );
if( mod )
Index: stg_time.cc
===================================================================
RCS file: /cvsroot/playerstage/code/stage/libstageplugin/Attic/stg_time.cc,v
retrieving revision 1.1.2.1
retrieving revision 1.1.2.2
diff -C2 -d -r1.1.2.1 -r1.1.2.2
*** stg_time.cc 4 Oct 2007 01:17:03 -0000 1.1.2.1
--- stg_time.cc 27 Nov 2007 05:36:02 -0000 1.1.2.2
***************
*** 28,32 ****
! #include "stage_internal.h"
#include "stg_time.h"
#include "math.h"
--- 28,32 ----
! #include "../libstage/stage.hh"
#include "stg_time.h"
#include "math.h"
***************
*** 54,61 ****
assert( this->driver );
! stg_world_t* world = driver->world;
! time->tv_sec = (int)floor(world->sim_time_ms / 1e3);
! time->tv_usec = (int)rint(fmod(world->sim_time_ms,1e3) * 1e3);
PRINT_DEBUG2( "time now %ld sec %ld usec", time->tv_sec, time->tv_usec );
--- 54,61 ----
assert( this->driver );
! StgWorld* world = driver->world;
! time->tv_sec = (int)floor(world->sim_time / 1e6);
! time->tv_usec = (int)rint(fmod(world->sim_time,1e6) * 1e6);
PRINT_DEBUG2( "time now %ld sec %ld usec", time->tv_sec, time->tv_usec );
***************
*** 70,76 ****
assert( this->driver );
! stg_world_t* world = driver->world;
! *time = world->sim_time_ms / 1e3;
PRINT_DEBUG1( "time now %f sec ", *time);
--- 70,76 ----
assert( this->driver );
! StgWorld* world = driver->world;
! *time = world->sim_time / 1e6;
PRINT_DEBUG1( "time now %f sec ", *time);
-------------------------------------------------------------------------
This SF.net email is sponsored by: Microsoft
Defy all challenges. Microsoft(R) Visual Studio 2005.
http://clk.atdmt.com/MRT/go/vse0120000070mrt/direct/01/
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit