|
From: <rdi...@us...> - 2009-05-15 06:43:02
|
Revision: 15497
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=15497&view=rev
Author: rdiankov
Date: 2009-05-15 06:42:56 +0000 (Fri, 15 May 2009)
Log Message:
-----------
added python binding to openrave via openravepy
Modified Paths:
--------------
pkg/trunk/3rdparty/openrave/Makefile
pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp
pkg/trunk/openrave_planning/openraveros/src/session.h
pkg/trunk/util/robot_self_filter/src/robotlinks_filter_node.cpp
Modified: pkg/trunk/3rdparty/openrave/Makefile
===================================================================
--- pkg/trunk/3rdparty/openrave/Makefile 2009-05-15 06:19:57 UTC (rev 15496)
+++ pkg/trunk/3rdparty/openrave/Makefile 2009-05-15 06:42:56 UTC (rev 15497)
@@ -2,7 +2,7 @@
SVN_DIR = openrave_svn
# Should really specify a revision
-SVN_REVISION = -r 768
+SVN_REVISION = -r 775
SVN_URL = https://openrave.svn.sourceforge.net/svnroot/openrave
#SVN_PATCH = fini_patch.patch
include $(shell rospack find mk)/svn_checkout.mk
Modified: pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp 2009-05-15 06:19:57 UTC (rev 15496)
+++ pkg/trunk/openrave_planning/openraveros/src/openraveros.cpp 2009-05-15 06:42:56 UTC (rev 15497)
@@ -97,11 +97,6 @@
int main(int argc, char ** argv)
{
- // Set up the output streams to support wide characters
- if (fwide(stdout,1) < 0) {
- printf("Unable to set stdout to wide characters\n");
- }
-
signal(SIGINT,sigint_handler); // control C
ros::init(argc,argv);
Modified: pkg/trunk/openrave_planning/openraveros/src/session.h
===================================================================
--- pkg/trunk/openrave_planning/openraveros/src/session.h 2009-05-15 06:19:57 UTC (rev 15496)
+++ pkg/trunk/openrave_planning/openraveros/src/session.h 2009-05-15 06:42:56 UTC (rev 15497)
@@ -359,8 +359,11 @@
}
int id = rand();
- while(id == 0 || _mapsessions.find(id) != _mapsessions.end())
- id = rand();
+ {
+ boost::mutex::scoped_lock lock(_mutexsession);
+ while(id == 0 || _mapsessions.find(id) != _mapsessions.end())
+ id = rand();
+ }
SessionState state;
@@ -386,6 +389,8 @@
state._pserver.reset(new ROSServer(id, new SessionSetViewerFunc(this), state._penv.get(), req.physicsengine, req.collisionchecker, req.viewer));
state._penv->AttachServer(state._pserver.get());
+
+ boost::mutex::scoped_lock lock(_mutexsession);
_mapsessions[id] = state;
res.sessionid = id;
Modified: pkg/trunk/util/robot_self_filter/src/robotlinks_filter_node.cpp
===================================================================
--- pkg/trunk/util/robot_self_filter/src/robotlinks_filter_node.cpp 2009-05-15 06:19:57 UTC (rev 15496)
+++ pkg/trunk/util/robot_self_filter/src/robotlinks_filter_node.cpp 2009-05-15 06:42:56 UTC (rev 15497)
@@ -97,7 +97,7 @@
};
RobotLinksFilter(const string& robotname, dReal convexpadding, bool bAccurateTiming) : _robotname(robotname), _convexpadding(convexpadding), _bAccurateTiming(bAccurateTiming)
- {
+ {
if( InitRobotLinksFromOpenRAVE(robotname) ) {
double tf_cache_time_secs;
s_pmasternode->param("~tf_cache_time_secs", tf_cache_time_secs, 10.0);
@@ -116,14 +116,10 @@
extrap_limit.fromSec(tf_extrap_limit_secs);
_tf->setExtrapolationLimit(extrap_limit);
ROS_INFO("RobotLinksFilter: tf extrapolation Limit: %f Seconds", tf_extrap_limit_secs);
- _pointcloudnotifier =
- new tf::MessageNotifier<robot_msgs::PointCloud>
- (_tf.get(), ros::Node::instance(),
- boost::bind(&RobotLinksFilter::PointCloudCallback,
- this, _1),
- "tilt_laser_cloud_filtered", "base_link",
- 50);
- ROS_ASSERT(_pointcloudnotifier);
+ _pointcloudnotifier.reset(new tf::MessageNotifier<robot_msgs::PointCloud>
+ (_tf.get(), ros::Node::instance(),
+ boost::bind(&RobotLinksFilter::PointCloudCallback, this, _1),
+ "tilt_laser_cloud_filtered", "base_link", 50));
}
else
ROS_ERROR("failed to init robot %s", robotname.c_str());
@@ -138,8 +134,7 @@
s_pmasternode->unadvertise("robotlinks_cloud_filtered");
}
- if( _pointcloudnotifier)
- delete _pointcloudnotifier;
+ _pointcloudnotifier.reset();
}
bool InitRobotLinksFromOpenRAVE(const string& robotname)
@@ -440,7 +435,7 @@
string _robotname;
dReal _convexpadding;
bool _bAccurateTiming; ///< if true, will interpolate the convex hulls for every time stamp
- tf::MessageNotifier<robot_msgs::PointCloud>* _pointcloudnotifier;
+ boost::shared_ptr<tf::MessageNotifier<robot_msgs::PointCloud> > _pointcloudnotifier;
};
int main(int argc, char ** argv)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|