|
From: <rdi...@us...> - 2008-11-28 11:04:56
|
Revision: 7400
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7400&view=rev
Author: rdiankov
Date: 2008-11-28 11:04:51 +0000 (Fri, 28 Nov 2008)
Log Message:
-----------
in progress openrave session server
Modified Paths:
--------------
pkg/trunk/3rdparty/openrave/Makefile
pkg/trunk/openrave_planning/openraveros/CMakeLists.txt
pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp
pkg/trunk/openrave_planning/openraveros/src/openraveros.h
pkg/trunk/openrave_planning/openraveros/src/session.h
pkg/trunk/openrave_planning/openraveros/srv/env_set.srv
pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv
pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp
pkg/trunk/openrave_planning/orrosplanning/src/plugindefs.h
pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.cpp
pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.h
Added Paths:
-----------
pkg/trunk/openrave_planning/openraveros/src/rosserver.h
Removed Paths:
-------------
pkg/trunk/openrave_planning/openraveros/src/session.cpp
Modified: pkg/trunk/3rdparty/openrave/Makefile
===================================================================
--- pkg/trunk/3rdparty/openrave/Makefile 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/3rdparty/openrave/Makefile 2008-11-28 11:04:51 UTC (rev 7400)
@@ -2,7 +2,7 @@
SVN_DIR = openrave_svn
# Should really specify a revision
-SVN_REVISION = -r 513
+SVN_REVISION = -r 521
SVN_URL = https://openrave.svn.sourceforge.net/svnroot/openrave
include $(shell rospack find mk)/svn_checkout.mk
Modified: pkg/trunk/openrave_planning/openraveros/CMakeLists.txt
===================================================================
--- pkg/trunk/openrave_planning/openraveros/CMakeLists.txt 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/CMakeLists.txt 2008-11-28 11:04:51 UTC (rev 7400)
@@ -4,5 +4,5 @@
rospack(openraveros)
genmsg()
gensrv()
-add_executable(openraveros src/openraveros.cpp)
-target_link_libraries (openraveros pthread openrave-core)
+rospack_add_executable(openraveros src/openraveros.cpp)
+target_link_libraries (openraveros openrave-core boost_thread)
Modified: pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp 2008-11-28 11:04:51 UTC (rev 7400)
@@ -24,126 +24,19 @@
//
// author: Rosen Diankov
#include "openraveros.h"
-#include <signal.h>
+#include "session.h"
-void sigint_handler(int);
-void* MainOpenRAVEThread(void*p);
-
-static EnvironmentBase* penv = NULL;
-static bool bDisplayGUI = false;
-static pthread_t s_mainThread;
-static boost::shared_ptr<RaveServerBase> s_server;
-static bool bThreadDestroyed = false;
-int g_argc;
-char** g_argv;
-
int main(int argc, char ** argv)
{
- g_argc = argc;
- g_argv = argv;
+ ros::init(argc,argv);
+ ros::node masternode("openraveserver");
- int nServPort = 4765;
- int nDebugLevel = 0;
-
- // Set up the output streams to support wide characters
- if (fwide(stdout,1) < 0) {
- printf("Unable to set stdout to wide characters\n");
- }
-
- // create environment and start a command-line controlled simulation
- penv = CreateEnvironment();
- if( penv == NULL )
+ if( !masternode.check_master() )
return -1;
- // parse command line arguments
- int i = 1;
- while(i < argc) {
- if( stricmp(argv[i], "-loadplugin") == 0 ) {
- penv->LoadPlugin(argv[i+1]);
- i += 2;
- }
- else if( stricmp(argv[i], "-gui") == 0 ) {
- bDisplayGUI = true;
- i++;
- }
- else if( stricmp(argv[i], "-d") == 0 ) {
- nDebugLevel = atoi(argv[i+1]);
- i += 2;
- }
- else if( stricmp(argv[i], "-server") == 0 ) {
- nServPort = atoi(argv[i+1]);
- i += 2;
- }
- else {
- RAVEPRINT(L"Error in input parameters at %s\ntype --help to see a list of command line options\n", argv[i]);
- return 0;
- }
- }
-
- // add a signal handler
- signal(SIGINT,sigint_handler); // control C
-
- penv->SetDebugLevel(nDebugLevel);
-
- if( nServPort > 0 ) {
- //penv->AttachServer(s_server.get());
- }
-
- bThreadDestroyed = false;
- if( pthread_create(&s_mainThread, NULL, MainOpenRAVEThread, NULL) ) {
- RAVEPRINT(L"failed to create main openrave thread\n");
- }
-
- while(!bThreadDestroyed) {
-#ifdef _WIN32
- Sleep(100);
-#else
- usleep(100000);
- //pthread_yield();
-#endif
- }
-
- if( penv != NULL ) {
- penv->GetViewer()->quitmainloop();
- penv->AttachViewer(NULL);
-
- RAVEPRINT(L"deleting the environment\n");
- delete penv; penv = NULL;
- }
-
- return 0;
-}
-
-// use to control openrave
-void* MainOpenRAVEThread(void*p)
-{
- penv->GetViewer()->main();
-
- if( !bThreadDestroyed ) {
- penv->GetViewer()->quitmainloop();
- penv->AttachViewer(NULL);
- //s_viewer.reset();
-
- if( penv != NULL ) {
- delete penv; penv = NULL;
- }
-
- bThreadDestroyed = true;
- }
+ boost::shared_ptr<SessionServer> sessionserver(new SessionServer());
+ masternode.spin();
- return NULL;
+ sessionserver.reset();
+ ros::fini();
}
-
-void sigint_handler(int)
-{
-
- if( !bThreadDestroyed ) {
-#ifndef _WIN32
- pthread_kill(s_mainThread, SIGINT);
-#else
- pthread_kill(s_mainThread, 0);
-#endif
- bThreadDestroyed = true;
- }
-
-}
Modified: pkg/trunk/openrave_planning/openraveros/src/openraveros.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/openraveros.h 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/src/openraveros.h 2008-11-28 11:04:51 UTC (rev 7400)
@@ -72,14 +72,55 @@
#define stricmp strcasecmp
#endif
-#include <boost/shared_ptr.hpp>
-
#include <openrave-core.h>
#include <ros/node.h>
-#include <rosthread/member_thread.h>
+#include <boost/thread/thread.hpp>
+#include <boost/thread/mutex.hpp>
+#include <boost/static_assert.hpp>
+#include <boost/bind.hpp>
+
+// services
+#include <openraveros/body_destroy.h>
+#include <openraveros/body_enable.h>
+#include <openraveros/body_getaabb.h>
+#include <openraveros/body_getaabbs.h>
+#include <openraveros/body_getdof.h>
+#include <openraveros/body_getlinks.h>
+#include <openraveros/body_setjointvalues.h>
+#include <openraveros/body_settransform.h>
+#include <openraveros/env_checkcollision.h>
+#include <openraveros/env_closefigures.h>
+#include <openraveros/env_createbody.h>
+#include <openraveros/env_createplanner.h>
+#include <openraveros/env_createproblem.h>
+#include <openraveros/env_createrobot.h>
+#include <openraveros/env_destroyproblem.h>
+#include <openraveros/env_getbodies.h>
+#include <openraveros/env_getbody.h>
+#include <openraveros/env_getrobots.h>
+#include <openraveros/env_loadplugin.h>
+#include <openraveros/env_loadscene.h>
+#include <openraveros/env_plot.h>
+#include <openraveros/env_raycollision.h>
+#include <openraveros/env_set.h>
+#include <openraveros/env_triangulate.h>
+#include <openraveros/env_wait.h>
+#include <openraveros/planner_init.h>
+#include <openraveros/planner_plan.h>
+#include <openraveros/problem_sendcommand.h>
+#include <openraveros/robot_controllersend.h>
+#include <openraveros/robot_controllerset.h>
+#include <openraveros/robot_getactivedof.h>
+#include <openraveros/robot_getactivevalues.h>
+#include <openraveros/robot_sensorgetdata.h>
+#include <openraveros/robot_sensorsend.h>
+#include <openraveros/robot_setactivedofs.h>
+#include <openraveros/robot_setactivevalues.h>
+#include <openraveros/robot_starttrajectory.h>
+
using namespace OpenRAVE;
-using namespace ros;
using namespace std;
+using namespace openraveros;
#endif
Added: pkg/trunk/openrave_planning/openraveros/src/rosserver.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/rosserver.h (rev 0)
+++ pkg/trunk/openrave_planning/openraveros/src/rosserver.h 2008-11-28 11:04:51 UTC (rev 7400)
@@ -0,0 +1,208 @@
+// Software License Agreement (BSD License)
+// Copyright (c) 2008, Willow Garage, Inc.
+// Redistribution and use in source and binary forms, with or without
+// modification, are permitted provided that the following conditions are met:
+// * Redistributions of source code must retain the above copyright notice,
+// this list of conditions and the following disclaimer.
+// * Redistributions in binary form must reproduce the above copyright
+// notice, this list of conditions and the following disclaimer in the
+// documentation and/or other materials provided with the distribution.
+// * The name of the author may not be used to endorse or promote products
+// derived from this software without specific prior written permission.
+//
+// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+// POSSIBILITY OF SUCH DAMAGE.
+//
+// author: Rosen Diankov
+
+#include "openraveros.h"
+
+class ROSServer : public RaveServerBase
+{
+public:
+ ROSServer(boost::shared_ptr<EnvironmentBase> penv) : RaveServerBase(penv.get()), _nNextFigureId(1), _nNextPlannerId(1) {
+ _penv = penv;
+ _bThreadDestroyed = false;
+ _fSimulationTimestep = 0.01;
+ _vgravity = Vector(0,0,-9.8f);
+ }
+ virtual ~ROSServer() {
+ Destroy();
+ }
+
+ virtual void Destroy()
+ {
+ Reset();
+
+ _penv->SetCollisionChecker(NULL);
+ _penv->SetPhysicsEngine(NULL);
+ _penv->AttachViewer(NULL);
+
+ // have to maintain a certain destruction order
+ _pphysics.reset();
+ _pcolchecker.reset();
+
+ if( !!_pviewer ) {
+ _pviewer->quitmainloop();
+ _threadviewer.join();
+ _pviewer.reset();
+ }
+ }
+
+ virtual void Reset()
+ {
+
+// pthread_mutex_lock(&_mutexWorker);
+// listWorkers.clear();
+// pthread_mutex_unlock(&_mutexWorker);
+// pthread_cond_signal(&_condWorker);
+//
+// FOREACH(it, s_mapFigureIds)
+// g_Environ.closegraph(it->second);
+// s_mapFigureIds.clear();
+
+ // destroy environment specific state: problems, planners, figures
+ _mapplanners.clear();
+ _mapproblems.clear();
+ }
+
+ virtual bool Init(int port)
+ {
+ return true;
+ }
+
+ /// worker thread called from the main environment thread
+ virtual void Worker()
+ {
+ }
+
+ virtual bool IsInit()
+ {
+ return true;
+ }
+
+ virtual bool IsClosing()
+ {
+ return false;
+ }
+
+ // called from threads other than the main worker to wait until
+ virtual void SyncWithWorkerThread()
+ {
+ }
+
+ bool body_destroy_srv(body_destroy::request& req, body_destroy::response& res);
+ bool body_enable_srv(body_enable::request& req, body_enable::response& res);
+ bool body_getaabb_srv(body_getaabb::request& req, body_getaabb::response& res);
+ bool body_getaabbs_srv(body_getaabbs::request& req, body_getaabbs::response& res);
+ bool body_getdof_srv(body_getdof::request& req, body_getdof::response& res);
+ bool body_getlinks_srv(body_getlinks::request& req, body_getlinks::response& res);
+ bool body_setjointvalues_srv(body_setjointvalues::request& req, body_setjointvalues::response& res);
+ bool body_settransform_srv(body_settransform::request& req, body_settransform::response& res);
+ bool env_checkcollision_srv(env_checkcollision::request& req, env_checkcollision::response& res);
+ bool env_closefigures_srv(env_closefigures::request& req, env_closefigures::response& res);
+ bool env_createbody_srv(env_createbody::request& req, env_createbody::response& res);
+ bool env_createplanner_srv(env_createplanner::request& req, env_createplanner::response& res);
+ bool env_createproblem_srv(env_createproblem::request& req, env_createproblem::response& res);
+ bool env_createrobot_srv(env_createrobot::request& req, env_createrobot::response& res);
+ bool env_destroyproblem_srv(env_destroyproblem::request& req, env_destroyproblem::response& res);
+ bool env_getbodies_srv(env_getbodies::request& req, env_getbodies::response& res);
+ bool env_getbody_srv(env_getbody::request& req, env_getbody::response& res);
+ bool env_getrobots_srv(env_getrobots::request& req, env_getrobots::response& res);
+ bool env_loadplugin_srv(env_loadplugin::request& req, env_loadplugin::response& res);
+ bool env_loadscene_srv(env_loadscene::request& req, env_loadscene::response& res);
+ bool env_plot_srv(env_plot::request& req, env_plot::response& res);
+ bool env_raycollision_srv(env_raycollision::request& req, env_raycollision::response& res);
+ bool env_set_srv(env_set::request& req, env_set::response& res)
+ {
+ if( req.setmask & env_set::request::Set_Simulation ) {
+ switch(req.sim_action) {
+ case env_set::request::SimAction_Start:
+ _penv->StartSimulation(_fSimulationTimestep);
+ break;
+ case env_set::request::SimAction_Stop:
+ _penv->StopSimulation();
+ break;
+ case env_set::request::SimAction_Timestep:
+ _fSimulationTimestep = req.sim_timestep;
+ _penv->StartSimulation(_fSimulationTimestep);
+ break;
+ }
+ }
+ if( req.setmask & env_set::request::Set_PhysicsEngine ) {
+ _pphysics.reset(_penv->CreatePhysicsEngine(req.physicsengine.c_str()));
+ _penv->SetPhysicsEngine(_pphysics.get());
+ if( !!_pphysics )
+ _pphysics->SetGravity(_vgravity);
+ }
+ if( req.setmask & env_set::request::Set_CollisionChecker ) {
+ int options = _penv->GetCollisionOptions();
+ _pcolchecker.reset(_penv->CreateCollisionChecker(req.collisionchecker.c_str()));
+ _penv->SetCollisionChecker(_pcolchecker.get());
+ _penv->SetCollisionOptions(options);
+ }
+ if( req.setmask & env_set::request::Set_Gravity ) {
+ _vgravity = Vector(req.gravity[0],req.gravity[1],req.gravity[2]);
+ if( !!_pphysics )
+ _pphysics->SetGravity(_vgravity);
+ }
+ if( req.setmask & env_set::request::Set_PublishAnytime ) {
+ _penv->SetPublishBodiesAnytime(req.publishanytime>0);
+ }
+ if( req.setmask & env_set::request::Set_DebugLevel ) {
+ _penv->SetDebugLevel(req.debuglevel);
+ }
+ if( req.setmask & env_set::request::Set_Viewer ) {
+ if( !!_pviewer ) {
+ _pviewer->quitmainloop();
+ // no need to wait for joins
+ //_threadviewer.join();
+ }
+
+ _pviewer.reset(_penv->CreateViewer(req.viewer.c_str()));
+ _penv->AttachViewer(_pviewer.get());
+ if( !!_pviewer )
+ _threadviewer = boost::thread(boost::bind(&RaveViewerBase::main, _pviewer.get()));
+ }
+
+ return true;
+ }
+
+ bool env_triangulate_srv(env_triangulate::request& req, env_triangulate::response& res);
+ bool env_wait_srv(env_wait::request& req, env_wait::response& res);
+ bool planner_init_srv(planner_init::request& req, planner_init::response& res);
+ bool planner_plan_srv(planner_plan::request& req, planner_plan::response& res);
+ bool problem_sendcommand_srv(problem_sendcommand::request& req, problem_sendcommand::response& res);
+ bool robot_controllersend_srv(robot_controllersend::request& req, robot_controllersend::response& res);
+ bool robot_controllerset_srv(robot_controllerset::request& req, robot_controllerset::response& res);
+ bool robot_getactivedof_srv(robot_getactivedof::request& req, robot_getactivedof::response& res);
+ bool robot_getactivevalues_srv(robot_getactivevalues::request& req, robot_getactivevalues::response& res);
+ bool robot_sensorgetdata_srv(robot_sensorgetdata::request& req, robot_sensorgetdata::response& res);
+ bool robot_sensorsend_srv(robot_sensorsend::request& req, robot_sensorsend::response& res);
+ bool robot_setactivedofs_srv(robot_setactivedofs::request& req, robot_setactivedofs::response& res);
+ bool robot_setactivevalues_srv(robot_setactivevalues::request& req, robot_setactivevalues::response& res);
+ bool robot_starttrajectory_srv(robot_starttrajectory::request& req, robot_starttrajectory::response& res);
+
+private:
+ boost::shared_ptr<EnvironmentBase> _penv; ///< the environment this instance of this session
+ boost::shared_ptr<PhysicsEngineBase> _pphysics;
+ boost::shared_ptr<CollisionCheckerBase> _pcolchecker;
+ boost::shared_ptr<RaveViewerBase> _pviewer;
+ map<int, boost::shared_ptr<PlannerBase> > _mapplanners;
+ map<int, boost::shared_ptr<ProblemInstance> > _mapproblems;
+ map<int, void*> _mapFigureIds;
+ int _nNextFigureId, _nNextPlannerId;
+ boost::thread _threadviewer;
+ bool _bThreadDestroyed;
+ float _fSimulationTimestep;
+ Vector _vgravity;
+};
Deleted: pkg/trunk/openrave_planning/openraveros/src/session.cpp
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/session.cpp 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/src/session.cpp 2008-11-28 11:04:51 UTC (rev 7400)
@@ -1,126 +0,0 @@
-// Software License Agreement (BSD License)
-// Copyright (c) 2008, Willow Garage, Inc.
-// Redistribution and use in source and binary forms, with or without
-// modification, are permitted provided that the following conditions are met:
-// * Redistributions of source code must retain the above copyright notice,
-// this list of conditions and the following disclaimer.
-// * Redistributions in binary form must reproduce the above copyright
-// notice, this list of conditions and the following disclaimer in the
-// documentation and/or other materials provided with the distribution.
-// * The name of the author may not be used to endorse or promote products
-// derived from this software without specific prior written permission.
-//
-// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
-// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
-// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
-// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
-// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
-// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
-// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
-// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
-// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
-// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-// POSSIBILITY OF SUCH DAMAGE.
-//
-// author: Rosen Diankov
-
-#include "openraveros.h"
-#include "session.h"
-
-// compile time assert RobotBase::DOF_X and CO_X
-class Session
-{
-public:
- Session() {
- }
- ~Session() {
- }
-
- void startros()
- {
- // check if thread launched
- ros::node* pnode = ros::node::instance();
-
- if( pnode && !pnode->check_master() ) {
- ros::fini();
- delete pnode;
- pnode = NULL;
- }
-
- if (!pnode) {
- int argc = 0;
- ros::init(argc,NULL);
- char strname[256] = "nohost";
- gethostname(strname, sizeof(strname));
- pnode = new ros::node(strname,);
- member_thread::startMemberFunctionThread<node>(pnode, &ros::node::spin);
- }
-
- if( !pnode->check_master() )
- return NULL;
-
- return pnode;
- }
-
- void advertise_session()
- {
- ros::node* pnode = startros();
- if( pnode == NULL )
- return;
-
- sessionhandle = pnode->advertise_service("openrave_session",&OpenraveSession::startsession,this);
- }
-
- bool startsession(roscpp_tutorials::simple_session::request& req, roscpp_tutorials::simple_session::response& res) {
- if( req.sessionid ) {
- }
- }
-
- bool getmap(StaticMap::request& req, StaticMap::response& res)
- {
- cout << "getmap!" << endl;
- return true;
- }
- bool getimage(PolledImage::request& req, PolledImage::response& res)
- {
- cout << "getimage!" << endl;
- return true;
- }
-};
-
-
-ROSServer::ROSServer()
-{
-}
-
-ROSServer::~ROSServer()
-{
-}
-
-void ROSServer::Destroy()
-{
-}
-
-void ROSServer::Reset()
-{
-}
-
-bool ROSServer::Init(int port)
-{
-}
-
-void ROSServer::Worker()
-{
-}
-
-bool ROSServer::IsInit()
-{
-}
-
-bool ROSServer::IsClosing()
-{
-}
-
-void ROSServer::SyncWithWorkerThread()
-{
-]
Modified: pkg/trunk/openrave_planning/openraveros/src/session.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/session.h 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/src/session.h 2008-11-28 11:04:51 UTC (rev 7400)
@@ -24,103 +24,274 @@
//
// author: Rosen Diankov
+#include "openraveros.h"
+#include "rosserver.h"
+
#include <openraveros/openrave_session.h>
-#include <openraveros/body_destroy.h>
-#include <openraveros/body_enable.h>
-#include <openraveros/body_getaabb.h>
-#include <openraveros/body_getaabbs.h>
-#include <openraveros/body_getdof.h>
-#include <openraveros/body_getlinks.h>
-#include <openraveros/body_setjointvalues.h>
-#include <openraveros/body_settransform.h>
-#include <openraveros/env_checkcollision.h>
-#include <openraveros/env_closefigures.h>
-#include <openraveros/env_createbody.h>
-#include <openraveros/env_createplanner.h>
-#include <openraveros/env_createproblem.h>
-#include <openraveros/env_createrobot.h>
-#include <openraveros/env_destroyproblem.h>
-#include <openraveros/env_getbodies.h>
-#include <openraveros/env_getbody.h>
-#include <openraveros/env_getrobots.h>
-#include <openraveros/env_loadplugin.h>
-#include <openraveros/env_loadscene.h>
-#include <openraveros/env_plot.h>
-#include <openraveros/env_raycollision.h>
-#include <openraveros/env_set.h>
-#include <openraveros/env_triangulate.h>
-#include <openraveros/env_wait.h>
-#include <openraveros/planner_init.h>
-#include <openraveros/planner_plan.h>
-#include <openraveros/problem_sendcommand.h>
-#include <openraveros/robot_controllersend.h>
-#include <openraveros/robot_controllerset.h>
-#include <openraveros/robot_getactivedof.h>
-#include <openraveros/robot_getactivevalues.h>
-#include <openraveros/robot_sensorgetdata.h>
-#include <openraveros/robot_sensorsend.h>
-#include <openraveros/robot_setactivedofs.h>
-#include <openraveros/robot_setactivevalues.h>
-using namespace openraveros;
+using namespace ros;
-class ROSServer : public RaveServerBase
+#define REFLECT_SERVICE(srvname) \
+ bool srvname##_srv(srvname::request& req, srvname::response& res) \
+ { \
+ SessionState state = getstate(req.sessionid); \
+ if( !state._pserver ) \
+ return false; \
+ state._pserver->srvname##_srv(req,res); \
+ }
+
+class SessionServer
{
+ class SessionState
+ {
+ public:
+ virtual ~SessionState() {
+ _penv.reset();
+ _pserver.reset();
+ }
+
+ boost::shared_ptr<ROSServer> _pserver;
+ boost::shared_ptr<EnvironmentBase> _penv;
+ };
+
public:
- ROSServer();
- virtual ~ROSServer();
+ SessionServer() {
+ }
+ virtual ~SessionServer() {
+ Destroy();
+ }
- virtual void Destroy();
- virtual void Reset();
+ bool Init() {
+ node* pnode = node::instance();
+ if( pnode == NULL )
+ return false;
- virtual bool Init(int port);
+ if( !pnode->advertise_service("openrave_session",&SessionServer::session_callback,this) )
+ return false;
- /// worker thread called from the main environment thread
- virtual void Worker();
+ // advertise persistent services
+ if( !pnode->advertise_service("body_destroy",&SessionServer::body_destroy_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("body_enable",&SessionServer::body_enable_srv,this,1,true) )
+ return false;
- virtual bool IsInit();
- virtual bool IsClosing();
+ if( !pnode->advertise_service("body_getaabb",&SessionServer::body_getaabb_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("body_getaabbs",&SessionServer::body_getaabbs_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("body_getdof",&SessionServer::body_getdof_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("body_getlinks",&SessionServer::body_getlinks_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("body_setjointvalues",&SessionServer::body_setjointvalues_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("body_settransform",&SessionServer::body_settransform_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_checkcollision",&SessionServer::env_checkcollision_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_closefigures",&SessionServer::env_closefigures_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_createbody",&SessionServer::env_createbody_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_createplanner",&SessionServer::env_createplanner_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_createproblem",&SessionServer::env_createproblem_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_createrobot",&SessionServer::env_createrobot_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_destroyproblem",&SessionServer::env_destroyproblem_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_getbodies",&SessionServer::env_getbodies_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_getbody",&SessionServer::env_getbody_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_getrobots",&SessionServer::env_getrobots_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_loadplugin",&SessionServer::env_loadplugin_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_loadscene",&SessionServer::env_loadscene_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_plot",&SessionServer::env_plot_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_raycollision",&SessionServer::env_raycollision_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_set",&SessionServer::env_set_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_triangulate",&SessionServer::env_triangulate_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("env_wait",&SessionServer::env_wait_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("planner_init",&SessionServer::planner_init_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("planner_plan",&SessionServer::planner_plan_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("problem_sendcommand",&SessionServer::problem_sendcommand_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_controllersend",&SessionServer::robot_controllersend_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_controllerset",&SessionServer::robot_controllerset_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_getactivedof",&SessionServer::robot_getactivedof_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_getactivevalues",&SessionServer::robot_getactivevalues_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_sensorgetdata",&SessionServer::robot_sensorgetdata_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_sensorsend",&SessionServer::robot_sensorsend_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_setactivedofs",&SessionServer::robot_setactivedofs_srv,this,1,true) )
+ return false;
+ if( !pnode->advertise_service("robot_setactivevalues",&SessionServer::robot_setactivevalues_srv,this,1,true) )
+ return false;
- // called from threads other than the main worker to wait until
- virtual void SyncWithWorkerThread();
+ return true;
+ }
+ void Destroy()
+ {
+ node* pnode = node::instance();
+ if( pnode == NULL )
+ return;
+
+ pnode->unadvertise_service("openrave_session");
+ pnode->unadvertise_service("body_destroy");
+ pnode->unadvertise_service("body_enable");
+ pnode->unadvertise_service("body_getaabb");
+ pnode->unadvertise_service("body_getaabbs");
+ pnode->unadvertise_service("body_getdof");
+ pnode->unadvertise_service("body_getlinks");
+ pnode->unadvertise_service("body_setjointvalues");
+ pnode->unadvertise_service("body_settransform");
+ pnode->unadvertise_service("env_checkcollision");
+ pnode->unadvertise_service("env_closefigures");
+ pnode->unadvertise_service("env_createbody");
+ pnode->unadvertise_service("env_createplanner");
+ pnode->unadvertise_service("env_createproblem");
+ pnode->unadvertise_service("env_createrobot");
+ pnode->unadvertise_service("env_destroyproblem");
+ pnode->unadvertise_service("env_getbodies");
+ pnode->unadvertise_service("env_getbody");
+ pnode->unadvertise_service("env_getrobots");
+ pnode->unadvertise_service("env_loadplugin");
+ pnode->unadvertise_service("env_loadscene");
+ pnode->unadvertise_service("env_plot");
+ pnode->unadvertise_service("env_raycollision");
+ pnode->unadvertise_service("env_set");
+ pnode->unadvertise_service("set_triangulate");
+ pnode->unadvertise_service("env_wait");
+ pnode->unadvertise_service("planner_init");
+ pnode->unadvertise_service("planner_plan");
+ pnode->unadvertise_service("problem_sendcommand");
+ pnode->unadvertise_service("robot_controllersend");
+ pnode->unadvertise_service("robot_controllerset");
+ pnode->unadvertise_service("robot_getactivevalues");
+ pnode->unadvertise_service("robot_sensorgetdata");
+ pnode->unadvertise_service("robot_sensorsend");
+ pnode->unadvertise_service("robot_setactivedofs");
+ pnode->unadvertise_service("robot_setactivevalues");
+ }
+
private:
- bool session_callback(openrave_session::request& openrave_session::response& res);
+ map<int,SessionState> _mapsessions;
+ boost::mutex _mutexsession;
- bool body_destroy_srv(body_destroy::request& body_destroy::response& res);
- bool body_enable_srv(body_enable::request& body_enable::response& res);
- bool body_getaabb_srv(body_getaabb::request& body_getaabb::response& res);
- bool body_getaabbs_srv(body_getaabbs::request& body_getaabbs::response& res);
- bool body_getdof_srv(body_getdof::request& body_getdof::response& res);
- bool body_getlinks_srv(body_getlinks::request& body_getlinks::response& res);
- bool body_setjointvalues_srv(body_setjointvalues::request& body_setjointvalues::response& res);
- bool body_settransform_srv(body_settransform::request& body_settransform::response& res);
- bool env_checkcollision_srv(env_checkcollision::request& env_checkcollision::response& res);
- bool env_closefigures_srv(env_closefigures::request& env_closefigures::response& res);
- bool env_createbody_srv(env_createbody::request& env_createbody::response& res);
- bool env_createplanner_srv(env_createplanner::request& env_createplanner::response& res);
- bool env_createproblem_srv(env_createproblem::request& env_createproblem::response& res);
- bool env_createrobot_srv(env_createrobot::request& env_createrobot::response& res);
- bool env_destroyproblem_srv(env_destroyproblem::request& env_destroyproblem::response& res);
- bool env_getbodies_srv(env_getbodies::request& env_getbodies::response& res);
- bool env_getbody_srv(env_getbody::request& env_getbody::response& res);
- bool env_getrobots_srv(env_getrobots::request& env_getrobots::response& res);
- bool env_loadplugin_srv(env_loadplugin::request& env_loadplugin::response& res);
- bool env_loadscene_srv(env_loadscene::request& env_loadscene::response& res);
- bool env_plot_srv(env_plot::request& env_plot::response& res);
- bool env_raycollision_srv(env_raycollision::request& env_raycollision::response& res);
- bool env_set_srv(env_set::request& env_set::response& res);
- bool env_triangulate_srv(env_triangulate::request& env_triangulate::response& res);
- bool env_wait_srv(env_wait::request& env_wait::response& res);
- bool planner_init_srv(planner_init::request& planner_init::response& res);
- bool planner_plan_srv(planner_plan::request& planner_plan::response& res);
- bool problem_sendcommand_srv(problem_sendcommand::request& problem_sendcommand::response& res);
- bool robot_controllersend_srv(robot_controllersend::request& robot_controllersend::response& res);
- bool robot_controllerset_srv(robot_controllerset::request& robot_controllerset::response& res);
- bool robot_getactivedof_srv(robot_getactivedof::request& robot_getactivedof::response& res);
- bool robot_getactivevalues_srv(robot_getactivevalues::request& robot_getactivevalues::response& res);
- bool robot_sensorgetdata_srv(robot_sensorgetdata::request& robot_sensorgetdata::response& res);
- bool robot_sensorsend_srv(robot_sensorsend::request& robot_sensorsend::response& res);
- bool robot_setactivedofs_srv(robot_setactivedofs::request& robot_setactivedofs::response& res);
- bool robot_setactivevalues_srv(robot_setactivevalues::request& robot_setactivevalues::response& res);
+ SessionState getstate(int sessionid)
+ {
+ boost::mutex::scoped_lock(_mutexsession);
+ if( _mapsessions.find(sessionid) == _mapsessions.end() )
+ return SessionState();
+ return _mapsessions[sessionid];
+ }
+
+ bool session_callback(openrave_session::request& req, openrave_session::response& res)
+ {
+ if( req.sessionid ) {
+ // destory the session
+ boost::mutex::scoped_lock(_mutexsession);
+ if( _mapsessions.find(req.sessionid) != _mapsessions.end() ) {
+ _mapsessions.erase(req.sessionid);
+ ROS_INFO("destroyed openrave session: %d\n", req.sessionid);
+ return true;
+ }
+
+ return false;
+ }
+
+ int id = rand();
+ while(id == 0 || _mapsessions.find(id) != _mapsessions.end())
+ id = rand();
+
+ SessionState state;
+ state._penv.reset(CreateEnvironment());
+ state._pserver.reset(new ROSServer(state._penv));
+
+ if( req.clone_sessionid ) {
+ // clone the environment from clone_sessionid
+ SessionState state = getstate(req.clone_sessionid);
+ if( !state._penv ) {
+ RAVEPRINT(L"failed to find session %d\n", req.clone_sessionid);
+ }
+ else {
+ // clone
+
+ }
+ }
+
+ _mapsessions[id] = state;
+ res.sessionid = id;
+
+ ROS_INFO("started openrave session: %d\n", id);
+ return true;
+ }
+
+ REFLECT_SERVICE(body_destroy)
+ REFLECT_SERVICE(body_enable)
+ REFLECT_SERVICE(body_getaabb)
+ REFLECT_SERVICE(body_getaabbs)
+ REFLECT_SERVICE(body_getdof)
+ REFLECT_SERVICE(body_getlinks)
+ REFLECT_SERVICE(body_setjointvalues)
+ REFLECT_SERVICE(body_settransform)
+ REFLECT_SERVICE(env_checkcollision)
+ REFLECT_SERVICE(env_closefigures)
+ REFLECT_SERVICE(env_createbody)
+ REFLECT_SERVICE(env_createplanner)
+ REFLECT_SERVICE(env_createproblem)
+ REFLECT_SERVICE(env_createrobot)
+ REFLECT_SERVICE(env_destroyproblem)
+ REFLECT_SERVICE(env_getbodies)
+ REFLECT_SERVICE(env_getbody)
+ REFLECT_SERVICE(env_getrobots)
+ REFLECT_SERVICE(env_loadplugin)
+ REFLECT_SERVICE(env_loadscene)
+ REFLECT_SERVICE(env_plot)
+ REFLECT_SERVICE(env_raycollision)
+ REFLECT_SERVICE(env_set)
+ REFLECT_SERVICE(env_triangulate)
+ REFLECT_SERVICE(env_wait)
+ REFLECT_SERVICE(planner_init)
+ REFLECT_SERVICE(planner_plan)
+ REFLECT_SERVICE(problem_sendcommand)
+ REFLECT_SERVICE(robot_controllersend)
+ REFLECT_SERVICE(robot_controllerset)
+ REFLECT_SERVICE(robot_getactivedof)
+ REFLECT_SERVICE(robot_getactivevalues)
+ REFLECT_SERVICE(robot_sensorgetdata)
+ REFLECT_SERVICE(robot_sensorsend)
+ REFLECT_SERVICE(robot_setactivedofs)
+ REFLECT_SERVICE(robot_setactivevalues)
+ REFLECT_SERVICE(robot_starttrajectory)
};
+
+// check that message constants match OpenRAVE constants
+BOOST_STATIC_ASSERT(ActiveDOFs::DOF_X==RobotBase::DOF_X);
+BOOST_STATIC_ASSERT(ActiveDOFs::DOF_Y==RobotBase::DOF_Y);
+BOOST_STATIC_ASSERT(ActiveDOFs::DOF_Z==RobotBase::DOF_Z);
+BOOST_STATIC_ASSERT(ActiveDOFs::DOF_RotationAxis==RobotBase::DOF_RotationAxis);
+BOOST_STATIC_ASSERT(ActiveDOFs::DOF_Rotation3D==RobotBase::DOF_Rotation3D);
+BOOST_STATIC_ASSERT(ActiveDOFs::DOF_RotationQuat==RobotBase::DOF_RotationQuat);
+
+BOOST_STATIC_ASSERT(env_checkcollision::request::CO_Distance==CO_Distance);
+BOOST_STATIC_ASSERT(env_checkcollision::request::CO_UseTolerance==CO_UseTolerance);
+BOOST_STATIC_ASSERT(env_checkcollision::request::CO_Contacts==CO_Contacts);
+BOOST_STATIC_ASSERT(env_checkcollision::request::CO_RayAnyHit==CO_RayAnyHit);
Modified: pkg/trunk/openrave_planning/openraveros/srv/env_set.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/env_set.srv 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/srv/env_set.srv 2008-11-28 11:04:51 UTC (rev 7400)
@@ -9,14 +9,18 @@
uint32 Set_Gravity=8
uint32 Set_PublishAnytime=16
uint32 Set_DebugLevel=32
-uint32 Set_Quit=64
+uint32 Set_Viewer=64
# validity depending on setmask
-string sim_option
+byte sim_action
+byte SimAction_Start=1
+byte SimAction_Stop=2
+byte SimAction_Timestep=3
float32 sim_timestep
string physicsengine
string collisionchecker
+string viewer
float32[3] gravity
byte publishanytime
byte debuglevel
Modified: pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv
===================================================================
--- pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/openraveros/srv/openrave_session.srv 2008-11-28 11:04:51 UTC (rev 7400)
@@ -1,5 +1,17 @@
+# Starts an openrave instance. This instance will have exclusive control over every object
+# that gets loaded.
+
# creates an openrave session
int32 sessionid
-int32 options
+
+# if non-zero, environment is cloned from the environment pointed by clone_sessionid
+# a clone uses the same collision checker and physics engine as its parent
+int32 clone_sessionid
+
+# mask of Clone* options
+byte clone_options
+
+byte CloneBodies=1 # copy all bodies
+
---
int32 sessionid
Modified: pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/orrosplanning/src/orrosplanningmain.cpp 2008-11-28 11:04:51 UTC (rev 7400)
@@ -27,18 +27,31 @@
#include "rosarmik.h"
-typedef void (*CREATECALLBACK)(PluginType type, const wchar_t* pname);
-EnvironmentBase* g_pEnviron = NULL;
+// declaring variables with stdcall can be a little complex
+#ifdef _MSC_VER
+#define PROT_STDCALL(name, paramlist) __stdcall name paramlist
+#define DECL_STDCALL(name, paramlist) __stdcall name paramlist
+
+#else
+
+#ifdef __x86_64__
+#define DECL_STDCALL(name, paramlist) name paramlist
+#else
+#define DECL_STDCALL(name, paramlist) __attribute__((stdcall)) name paramlist
+#endif
+
+#endif // _MSC_VER
+
// need c linkage
extern "C" {
-InterfaceBase* DECL_STDCALL(ORCreate, (PluginType type, wchar_t* name))
+InterfaceBase* DECL_STDCALL(ORCreate, (PluginType type, wchar_t* name, EnvironmentBase* penv))
{
switch(type) {
case PT_InverseKinematicsSolver:
if( wcsicmp(name, L"ROSArmIK") == 0 )
- return new ROSArmIK();
+ return new ROSArmIK(penv);
break;
default:
@@ -60,10 +73,4 @@
return true;
}
-void DECL_STDCALL(OpenPlugin, (void* pcallback, EnvironmentBase* penv))
-{
- RaveSetEnvironment(penv);
- g_pEnviron = penv;
}
-
-}
Modified: pkg/trunk/openrave_planning/orrosplanning/src/plugindefs.h
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/src/plugindefs.h 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/orrosplanning/src/plugindefs.h 2008-11-28 11:04:51 UTC (rev 7400)
@@ -55,22 +55,6 @@
#include <sys/timeb.h> // ftime(), struct timeb
-// declaring variables with stdcall can be a little complex
-#ifdef _MSC_VER
-
-#define PROT_STDCALL(name, paramlist) __stdcall name paramlist
-#define DECL_STDCALL(name, paramlist) __stdcall name paramlist
-
-#else
-
-#ifdef __x86_64__
-#define DECL_STDCALL(name, paramlist) name paramlist
-#else
-#define DECL_STDCALL(name, paramlist) __attribute__((stdcall)) name paramlist
-#endif
-
-#endif // _MSC_VER
-
template<class T>
inline T CLAMP_ON_RANGE(T value, T min, T max)
{
@@ -160,6 +144,4 @@
#include <rave/rave.h>
using namespace OpenRAVE;
-extern EnvironmentBase* g_pEnviron;
-
#endif
Modified: pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.cpp
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.cpp 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.cpp 2008-11-28 11:04:51 UTC (rev 7400)
@@ -32,7 +32,7 @@
inline T SQR(T x) { return x * x; }
#endif
-ROSArmIK::ROSArmIK() : IkSolverBase()
+ROSArmIK::ROSArmIK(EnvironmentBase* penv) : IkSolverBase(penv)
{
}
@@ -211,7 +211,7 @@
continue;
COLLISIONREPORT report;
- if( bCheckEnvCollision && g_pEnviron->CheckCollision(_probot, &report) ) {
+ if( bCheckEnvCollision && GetEnv()->CheckCollision(_probot, &report) ) {
if( report.plink1 != NULL && report.plink2 != NULL ) {
RAVELOG(L"WAMIK: collision %S:%S with %S:%S\n", report.plink1->GetParent()->GetName(), report.plink1->GetName(), report.plink2->GetParent()->GetName(), report.plink2->GetName());
}
@@ -319,7 +319,7 @@
if( _probot->CheckSelfCollision() )
continue;
- if( bCheckEnvCollision && g_pEnviron->CheckCollision(_probot) )
+ if( bCheckEnvCollision && GetEnv()->CheckCollision(_probot) )
continue;
qSolutions.push_back(vravesol);
@@ -373,7 +373,7 @@
continue;
COLLISIONREPORT report;
- if( bCheckEnvCollision && g_pEnviron->CheckCollision(_probot, &report) ) {
+ if( bCheckEnvCollision && GetEnv()->CheckCollision(_probot, &report) ) {
if( report.plink1 != NULL && report.plink2 != NULL ) {
RAVELOG(L"WAMIK: collision %S:%S with %S:%S\n", report.plink1->GetParent()->GetName(), report.plink1->GetName(), report.plink2->GetParent()->GetName(), report.plink2->GetName());
}
@@ -451,7 +451,7 @@
if( _probot->CheckSelfCollision() )
continue;
- if( bCheckEnvCollision && g_pEnviron->CheckCollision(_probot) )
+ if( bCheckEnvCollision && GetEnv()->CheckCollision(_probot) )
continue;
qSolutions.push_back(vravesol);
Modified: pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.h
===================================================================
--- pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.h 2008-11-28 08:10:49 UTC (rev 7399)
+++ pkg/trunk/openrave_planning/orrosplanning/src/rosarmik.h 2008-11-28 11:04:51 UTC (rev 7400)
@@ -32,7 +32,7 @@
class ROSArmIK : public IkSolverBase
{
public:
- ROSArmIK();
+ ROSArmIK(EnvironmentBase* penv);
virtual bool Init(RobotBase* probot, const RobotBase::Manipulator* pmanip, int options);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|