|
From: <hsu...@us...> - 2008-09-02 18:33:58
|
Revision: 3868
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3868&view=rev
Author: hsujohnhsu
Date: 2008-09-02 18:33:55 +0000 (Tue, 02 Sep 2008)
Log Message:
-----------
fix to pr2.xml ptz tilt axis joint.
update ptz controller to use ros controls through wx_camera_panel.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-09-02 18:33:55 UTC (rev 3868)
@@ -12,6 +12,7 @@
rospack_add_library(Ros_Camera src/Ros_Camera.cc)
rospack_add_library(Ros_Laser src/Ros_Laser.cc)
rospack_add_library(Ros_Node src/Ros_Node.cc)
+rospack_add_library(Ros_PTZ src/Ros_PTZ.cc)
rospack_add_library(P3D src/P3D.cc)
rospack_add_library(gazebo_actuators src/gazebo_actuators.cpp)
rospack_add_library(test_actuators src/test_actuators.cpp)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh 2008-09-02 18:33:55 UTC (rev 3868)
@@ -31,6 +31,13 @@
#include <gazebo/Param.hh>
#include <gazebo/Controller.hh>
+// ros messages
+#include <ros/node.h>
+
+// messages for controlling ptz
+#include <axis_cam/PTZActuatorState.h>
+#include <axis_cam/PTZActuatorCmd.h>
+
namespace gazebo
{
class HingeJoint;
@@ -112,6 +119,30 @@
private: Param<std::string> *panJointNameP;
private: Param<std::string> *tiltJointNameP;
+ private: Param<std::string> *commandTopicNameP;
+ private: Param<std::string> *stateTopicNameP;
+
+ // pointer to ros node
+ private: ros::node *rosnode;
+ // ros message
+ private: axis_cam::PTZActuatorState PTZStateMessage;
+ private: axis_cam::PTZActuatorCmd PTZControlMessage;
+
+ // receive message
+ private: void PTZCommandReceived();
+
+ // topic name
+ private: std::string commandTopicName;
+ private: std::string stateTopicName;
+
+ // frame transform name, should match link name
+ // FIXME: extract link name directly? currently using joint names
+ private: std::string panFrameName;
+ private: std::string tiltFrameName;
+
+ // A mutex to lock access to fields that are used in message callbacks
+ private: ros::thread::mutex lock;
+
};
/** /} */
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2008-09-02 18:33:55 UTC (rev 3868)
@@ -27,6 +27,7 @@
<depend package="mechanism_control" />
<depend package="wg_robot_description_parser" />
<depend package="tinyxml" />
+<depend package="axis_cam" />
<export>
<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib" />
</export>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc 2008-09-02 18:33:55 UTC (rev 3868)
@@ -36,11 +36,12 @@
#include <gazebo/GazeboError.hh>
#include <gazebo/ControllerFactory.hh>
#include <gazebo/HingeJoint.hh>
-#include <gazebo/Ros_PTZ.hh>
+#include <gazebo_plugin/Ros_PTZ.hh>
+
using namespace gazebo;
-GZ_REGISTER_STATIC_CONTROLLER("ros_ptz", Ros_PTZ);
+GZ_REGISTER_DYNAMIC_CONTROLLER("Ros_PTZ", Ros_PTZ);
////////////////////////////////////////////////////////////////////////////////
// Constructor
@@ -62,6 +63,20 @@
this->tiltJointNameP = new Param<std::string>("tiltJoint", "", 1);
this->motionGainP = new Param<double>("motionGain",2,0);
this->forceP = new Param<double>("force",10,0);
+ this->commandTopicNameP = new Param<std::string>("commandTopicName","PTZ_cmd",0);
+ this->stateTopicNameP = new Param<std::string>("stateTopicName","PTZ_state",0);
+
+ rosnode = ros::g_node; // comes from where?
+ int argc = 0;
+ char** argv = NULL;
+ if (rosnode == NULL)
+ {
+ // this only works for a single camera.
+ ros::init(argc,argv);
+ rosnode = new ros::node("ros_gazebo",ros::node::DONT_HANDLE_SIGINT);
+ printf("-------------------- starting node in camera \n");
+ }
+
}
////////////////////////////////////////////////////////////////////////////////
@@ -80,6 +95,8 @@
delete this->tiltJointNameP;
delete this->motionGainP;
delete this->forceP;
+ delete this->commandTopicNameP;
+ delete this->stateTopicNameP;
}
////////////////////////////////////////////////////////////////////////////////
@@ -95,10 +112,24 @@
this->tiltJointNameP->Load(node);
this->motionGainP->Load(node);
this->forceP->Load(node);
+ this->commandTopicNameP->Load(node);
+ this->stateTopicNameP->Load(node);
this->panJoint = dynamic_cast<HingeJoint*>(this->myParent->GetJoint(this->panJointNameP->GetValue()));
this->tiltJoint = dynamic_cast<HingeJoint*>(this->myParent->GetJoint(this->tiltJointNameP->GetValue()));
+ this->commandTopicName = this->commandTopicNameP->GetValue();
+ this->stateTopicName = this->stateTopicNameP->GetValue();
+
+ this->panFrameName = this->panJointNameP->GetValue();
+ this->tiltFrameName = this->tiltJointNameP->GetValue();
+
+ std::cout << " publishing state topic for ptz " << this->stateTopicName << std::endl;
+ std::cout << " subscribing command topic for ptz " << this->commandTopicName << std::endl;
+
+ rosnode->advertise<axis_cam::PTZActuatorState>(this->stateTopicName);
+ rosnode->subscribe( commandTopicName, PTZControlMessage, &Ros_PTZ::PTZCommandReceived,this);
+
if (!this->panJoint)
gzthrow("couldn't get pan hinge joint");
@@ -107,6 +138,14 @@
}
+void Ros_PTZ::PTZCommandReceived()
+{
+ this->lock.lock();
+ this->cmdPan = PTZControlMessage.pan.cmd*M_PI/180.0;
+ this->cmdTilt = PTZControlMessage.tilt.cmd*M_PI/180.0;
+ this->lock.unlock();
+}
+
////////////////////////////////////////////////////////////////////////////////
/// Save the controller.
void Ros_PTZ::SaveChild(std::string &prefix, std::ostream &stream)
@@ -134,13 +173,14 @@
// Update the controller
void Ros_PTZ::UpdateChild()
{
- this->ptzIface->Lock(1);
+ //this->ptzIface->Lock(1);
- this->cmdPan = this->ptzIface->data->cmd_pan;
- this->cmdTilt = this->ptzIface->data->cmd_tilt;
+ // pan tilt command set in void Ros_PTZ::PTZCommandReceived() rather than from Iface
+ //this->cmdPan = this->ptzIface->data->cmd_pan;
+ //this->cmdTilt = this->ptzIface->data->cmd_tilt;
//this->cmdZoom = this->hfov / this->ptzIface->data->cmd_zoom;
- this->ptzIface->Unlock();
+ //this->ptzIface->Unlock();
// Apply joint limits to commanded pan/tilt angles
if (this->cmdTilt > M_PI*0.3)
@@ -165,6 +205,8 @@
float tilt = this->cmdTilt - this->tiltJoint->GetAngle();
float pan = this->cmdPan - this->panJoint->GetAngle();
+ std::cout << "command received : " << this->cmdPan << ":" << this->cmdTilt;
+ std::cout << " state : " << this->panJoint->GetAngle() << ":" << this->tiltJoint->GetAngle() << std::endl;
this->tiltJoint->SetParam( dParamVel, **(this->motionGainP) * tilt);
this->tiltJoint->SetParam( dParamFMax, **(this->forceP) );
@@ -199,5 +241,16 @@
// New data is available
this->ptzIface->Post();
+
+ this->lock.lock();
+ // also put data into ros message
+ PTZStateMessage.pan.pos_valid =1;
+ PTZStateMessage.pan.pos = this->panJoint->GetAngle();
+ PTZStateMessage.tilt.pos_valid=1;
+ PTZStateMessage.tilt.pos = this->tiltJoint->GetAngle();
+ // publish topic
+ this->rosnode->publish(this->stateTopicName,PTZStateMessage);
+ this->lock.unlock();
+
}
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-02 18:33:55 UTC (rev 3868)
@@ -30,19 +30,23 @@
<verbatim key="controllers"> <!-- The key attribute is needed noly if multiple <xml> tags are in the same <map> tag -->
<!-- ptz camera controls -->
- <controller:generic_ptz name="ptz_cam_left_controller">
+ <controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
+ <commandTopicName>PTZL_cmd</commandTopicName>
+ <stateTopicName>PTZL_state</stateTopicName>
<interface:ptz name="ptz_left_iface" />
- </controller:generic_ptz>
+ </controller:Ros_PTZ>
- <controller:generic_ptz name="ptz_cam_right_controller">
+ <controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
+ <commandTopicName>PTZR_cmd</commandTopicName>
+ <stateTopicName>PTZR_state</stateTopicName>
<interface:ptz name="ptz_right_iface" />
- </controller:generic_ptz>
+ </controller:Ros_PTZ>
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-02 18:33:55 UTC (rev 3868)
@@ -30,19 +30,23 @@
<verbatim key="controllers"> <!-- The key attribute is needed noly if multiple <xml> tags are in the same <map> tag -->
<!-- ptz camera controls -->
- <controller:generic_ptz name="ptz_cam_left_controller">
+ <controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
+ <commandTopicName>PTZL_cmd</commandTopicName>
+ <stateTopicName>PTZL_state</stateTopicName>
<interface:ptz name="ptz_left_iface" />
- </controller:generic_ptz>
+ </controller:Ros_PTZ>
- <controller:generic_ptz name="ptz_cam_right_controller">
+ <controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
+ <commandTopicName>PTZR_cmd</commandTopicName>
+ <stateTopicName>PTZR_state</stateTopicName>
<interface:ptz name="ptz_right_iface" />
- </controller:generic_ptz>
+ </controller:Ros_PTZ>
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-09-02 18:29:06 UTC (rev 3867)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-09-02 18:33:55 UTC (rev 3868)
@@ -831,7 +831,7 @@
<limit min=" ptz_pan_min_limit" max="ptz_pan_max_limit" effort="10" velocity="5" />
</joint>
<joint name="ptz_tilt_left_joint" type="revolute">
- <axis xyz=" 0 0 1 " /> <!-- direction of the joint in a local coordinate frame -->
+ <axis xyz=" 0 1 0 " /> <!-- direction of the joint in a local coordinate frame -->
<anchor xyz="0 0 0 " /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
<limit min=" ptz_tilt_min_limit" max="ptz_tilt_max_limit" effort="10" velocity="5" />
</joint>
@@ -841,7 +841,7 @@
<limit min=" ptz_pan_min_limit" max="ptz_pan_max_limit" effort="10" velocity="5" />
</joint>
<joint name="ptz_tilt_right_joint" type="revolute">
- <axis xyz=" 0 0 1 " /> <!-- direction of the joint in a local coordinate frame -->
+ <axis xyz=" 0 1 0 " /> <!-- direction of the joint in a local coordinate frame -->
<anchor xyz="0 0 0 " /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
<limit min=" ptz_tilt_min_limit" max="ptz_tilt_max_limit" effort="10" velocity="5" />
</joint>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2008-09-02 22:55:08
|
Revision: 3879
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3879&view=rev
Author: isucan
Date: 2008-09-02 22:55:04 +0000 (Tue, 02 Sep 2008)
Log Message:
-----------
some documentation + changing message NamedKinematicPath to DisplayKinematicPath
Modified Paths:
--------------
pkg/trunk/motion_planning/ompl/code/ompl/base/General.h
pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp
pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h
pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp
pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp
pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp
pkg/trunk/nav/fake_localization/fake_localization.cpp
pkg/trunk/nav/fake_localization/manifest.xml
Added Paths:
-----------
pkg/trunk/robot_msgs/msg/DisplayKinematicPath.msg
Removed Paths:
-------------
pkg/trunk/robot_msgs/msg/NamedKinematicPath.msg
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/General.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/General.h 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/General.h 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
@@ -66,25 +66,25 @@
<hr>
- @section Sampling-based motion planners
+ @section sampling_planners Sampling-based motion planners
- This class of motion planner typically needs the ability to sample
+ This class of motion planners typically needs the ability to sample
the state (configuration) space of the robot(s) planning is done
for. To allow this, an implementation of StateValidityChecker must
be provided. This implementation will most likely depend on a
collision detector.
- @subsection Kinematic motion planners
+ @subsection kinematic_planners Kinematic motion planners
- @ref RRT
- @ref LazyRRT
- @ref SBL
- @subsection Kinodynamic motion planners
+ @subsection kinodynamic_planners Kinodynamic motion planners
- None implemented yet
- @section Grid-based motion planners
+ @section grid_planners Grid-based motion planners
- Not included yet
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/src/time.cpp 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** This file is taken from ROS, adaptations by Ioan Sucan */
+/* This file is taken from ROS, adaptations by Ioan Sucan */
#include "ompl/base/util/time.h"
#include <cmath>
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/time.h 2008-09-02 22:55:04 UTC (rev 3879)
@@ -36,7 +36,7 @@
#ifndef OMPL_TIME_
#define OMPL_TIME_
-/** This file is taken from ROS, adaptations by Ioan Sucan */
+/* This file is taken from ROS, adaptations by Ioan Sucan */
#include <iostream>
#include <cmath>
Modified: pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/base/util/types.h 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** This file is taken from ROS */
+/* This file is taken from ROS */
#ifndef OMPL_TYPES_
#define OMPL_TYPES_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_LAZY_RRT_
#define OMPL_EXTENSION_SAMPLINGBASED_KINEMATIC_EXTENSION_LAZY_RRT_
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,14 +32,19 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
- @subsubsection RRT (Rapidly-exploring Random Trees)
+ @subsubsection RRT Rapidly-exploring Random Trees (RRT)
@par Short description
-
+ The basic idea of RRT is that it samples a random state qr in the
+ state space, then finds the state qc among the previously seen
+ states that is closest to qr and expands from qc towards qr, until
+ a state qm is reached and qm is the new state to be visited.
+
+
@par External documentation
@link http://en.wikipedia.org/wiki/Rapidly-exploring_random_tree
@link http://msl.cs.uiuc.edu/~lavalle/rrtpubs.html
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/LazyRRT.cpp 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#include "ompl/extension/samplingbased/kinematic/extension/rrt/LazyRRT.h"
#include <cassert>
Modified: pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/ompl/code/ompl/extension/samplingbased/kinematic/extension/rrt/src/RRT.cpp 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#include "ompl/extension/samplingbased/kinematic/extension/rrt/RRT.h"
Modified: pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-09-02 22:55:04 UTC (rev 3879)
@@ -33,7 +33,7 @@
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/** This is a simple program for requesting a motion plan */
@@ -41,7 +41,7 @@
#include <ros/time.h>
#include <robot_srvs/KinematicPlanState.h>
#include <robot_srvs/KinematicPlanLinkPosition.h>
-#include <robot_msgs/NamedKinematicPath.h>
+#include <robot_msgs/DisplayKinematicPath.h>
#include <std_msgs/RobotBase2DOdom.h>
class PlanKinematicPath : public ros::node
@@ -50,7 +50,7 @@
PlanKinematicPath(void) : ros::node("plan_kinematic_path")
{
- advertise<robot_msgs::NamedKinematicPath>("display_kinematic_path", 1);
+ advertise<robot_msgs::DisplayKinematicPath>("display_kinematic_path", 1);
m_basePos[0] = m_basePos[1] = m_basePos[2] = 0.0;
m_haveBasePos = false;
@@ -78,7 +78,7 @@
req.params.model_id = "pr2::base";
req.params.distance_metric = "L2Square";
- req.params.planner_id = "SBL";
+ req.params.planner_id = "LazyRRT";
req.threshold = 0.01;
req.interpolate = 1;
req.times = 1;
@@ -159,8 +159,9 @@
void performCall(robot_srvs::KinematicPlanState::request &req)
{
robot_srvs::KinematicPlanState::response res;
- robot_msgs::NamedKinematicPath dpath;
-
+ robot_msgs::DisplayKinematicPath dpath;
+ dpath.frame_id = "FRAMEID_MAP";
+
if (ros::service::call("plan_kinematic_path_state", req, res))
{
unsigned int nstates = res.path.get_states_size();
@@ -227,8 +228,9 @@
void performCall(robot_srvs::KinematicPlanLinkPosition::request &req)
{
robot_srvs::KinematicPlanLinkPosition::response res;
- robot_msgs::NamedKinematicPath dpath;
-
+ robot_msgs::DisplayKinematicPath dpath;
+ dpath.frame_id = "FRAMEID_MAP";
+
if (ros::service::call("plan_kinematic_path_position", req, res))
{
unsigned int nstates = res.path.get_states_size();
Modified: pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/motion_planning/planning_world_viewer/src/planning_world_viewer.cpp 2008-09-02 22:55:04 UTC (rev 3879)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
@@ -89,7 +89,7 @@
#include <planning_node_util/cnode.h>
#include <rosthread/mutex.h>
-#include <robot_msgs/NamedKinematicPath.h>
+#include <robot_msgs/DisplayKinematicPath.h>
#include <display_ode/displayODE.h>
#include <vector>
@@ -273,7 +273,7 @@
display_ode::DisplayODESpaces m_spaces;
ros::thread::mutex m_displayLock;
- robot_msgs::NamedKinematicPath m_displayPath;
+ robot_msgs::DisplayKinematicPath m_displayPath;
bool m_follow;
bool m_displayRobot;
bool m_displayObstacles;
Modified: pkg/trunk/nav/fake_localization/fake_localization.cpp
===================================================================
--- pkg/trunk/nav/fake_localization/fake_localization.cpp 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/nav/fake_localization/fake_localization.cpp 2008-09-02 22:55:04 UTC (rev 3879)
@@ -54,7 +54,8 @@
@section topic ROS topics
Subscribes to (name/type):
-- @b "odom"/RobotBase2DOdom : robot's odometric pose. Only the position information is used (velocity is ignored).
+- @b "base_pos"/Pose3DEulerFloat32 : robot's odometric pose. Only the position information is used (velocity is ignored).
+- @b "initialpose"/Pose2DFloat32 : robot's odometric pose. Only the position information is used (velocity is ignored).
Publishes to (name / type):
- @b "localizedpose"/RobotBase2DOdom : robot's localized map pose. Only the position information is set (no velocity).
@@ -74,6 +75,7 @@
#include <std_msgs/RobotBase2DOdom.h>
#include <std_msgs/ParticleCloud2D.h>
#include <std_msgs/Pose2DFloat32.h>
+#include <robot_msgs/Pose3DEulerFloat32.h>
#include <math_utils/angles.h>
#include <rosTF/rosTF.h>
@@ -95,7 +97,8 @@
m_particleCloud.set_particles_size(1);
param("max_publish_frequency", m_maxPublishFrequency, 0.5);
- subscribe("odom", m_odomMsg, &FakeOdomNode::odomReceived);
+
+ subscribe("base_pos", m_basePosMsg, &FakeOdomNode::basePosReceived);
subscribe("initialpose", m_iniPos, &FakeOdomNode::initialPoseReceived);
}
@@ -108,14 +111,14 @@
private:
- rosTFServer *m_tfServer;
- ros::Time m_lastUpdate;
- double m_maxPublishFrequency;
+ rosTFServer *m_tfServer;
+ ros::Time m_lastUpdate;
+ double m_maxPublishFrequency;
- std_msgs::RobotBase2DOdom m_odomMsg;
- std_msgs::ParticleCloud2D m_particleCloud;
- std_msgs::RobotBase2DOdom m_currentOdom;
- std_msgs::Pose2DFloat32 m_iniPos;
+ robot_msgs::Pose3DEulerFloat32 m_basePosMsg;
+ std_msgs::ParticleCloud2D m_particleCloud;
+ std_msgs::RobotBase2DOdom m_currentPos;
+ std_msgs::Pose2DFloat32 m_iniPos;
void initialPoseReceived(void)
@@ -123,7 +126,7 @@
update();
}
- void odomReceived(void)
+ void basePosReceived(void)
{
update();
}
@@ -135,26 +138,29 @@
m_lastUpdate = ros::Time::now();
- m_currentOdom = m_odomMsg;
+ m_currentPos.header = m_basePosMsg.header;
+ m_currentPos.pos.x = m_basePosMsg.position.x;
+ m_currentPos.pos.y = m_basePosMsg.position.y;
+ m_currentPos.pos.th = m_basePosMsg.orientation.yaw;
- m_currentOdom.pos.x += m_iniPos.x;
- m_currentOdom.pos.y += m_iniPos.y;
- m_currentOdom.pos.th = math_utils::normalize_angle(m_currentOdom.pos.th + m_iniPos.th);
- m_currentOdom.header.frame_id = "FRAMEID_MAP";
+ m_currentPos.pos.x += m_iniPos.x;
+ m_currentPos.pos.y += m_iniPos.y;
+ m_currentPos.pos.th = math_utils::normalize_angle(m_currentPos.pos.th + m_iniPos.th);
+ m_currentPos.header.frame_id = "FRAMEID_MAP";
m_tfServer->sendEuler("FRAMEID_ROBOT",
"FRAMEID_MAP",
- m_currentOdom.pos.x,
- m_currentOdom.pos.y,
+ m_currentPos.pos.x,
+ m_currentPos.pos.y,
0.0,
- m_currentOdom.pos.th,
+ m_currentPos.pos.th,
0.0,
0.0,
- m_currentOdom.header.stamp);
+ m_currentPos.header.stamp);
- publish("localizedpose", m_currentOdom);
+ publish("localizedpose", m_currentPos);
- m_particleCloud.particles[0] = m_currentOdom.pos;
+ m_particleCloud.particles[0] = m_currentPos.pos;
publish("particlecloud", m_particleCloud);
}
Modified: pkg/trunk/nav/fake_localization/manifest.xml
===================================================================
--- pkg/trunk/nav/fake_localization/manifest.xml 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/nav/fake_localization/manifest.xml 2008-09-02 22:55:04 UTC (rev 3879)
@@ -3,7 +3,7 @@
<author>Ioan A. Sucan</author>
<license>BSD</license>
<depend package="roscpp" />
- <depend package="std_msgs" />
+ <depend package="robot_msgs" />
<depend package="rosTF" />
<depend package="math_utils" />
</package>
Added: pkg/trunk/robot_msgs/msg/DisplayKinematicPath.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/DisplayKinematicPath.msg (rev 0)
+++ pkg/trunk/robot_msgs/msg/DisplayKinematicPath.msg 2008-09-02 22:55:04 UTC (rev 3879)
@@ -0,0 +1,5 @@
+# The definition of a kinematic path that has a name
+# The name identifies the part of the robot the path is for
+string frame_id
+string name
+KinematicPath path
Deleted: pkg/trunk/robot_msgs/msg/NamedKinematicPath.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/NamedKinematicPath.msg 2008-09-02 22:20:42 UTC (rev 3878)
+++ pkg/trunk/robot_msgs/msg/NamedKinematicPath.msg 2008-09-02 22:55:04 UTC (rev 3879)
@@ -1,5 +0,0 @@
-# The definition of a kinematic path that has a name
-# The name identifies the part of the robot the path is for
-# This is useful in displaying paths
-string name
-KinematicPath path
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <stu...@us...> - 2008-09-02 23:44:36
|
Revision: 3881
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3881&view=rev
Author: stuglaser
Date: 2008-09-02 23:44:37 +0000 (Tue, 02 Sep 2008)
Log Message:
-----------
Moved Pid out of the controller namespace.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh
pkg/trunk/drivers/simulator/gazebo_plugin/src/Pr2_Actarray.cc
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/pid.h
pkg/trunk/mechanism/mechanism_model/src/pid.cpp
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh 2008-09-02 23:34:45 UTC (rev 3880)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Pr2_Actarray.hh 2008-09-02 23:44:37 UTC (rev 3881)
@@ -91,7 +91,7 @@
private: Joint *joints[GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
// we'll declare a pid controller for each hinger/slider/... joint
- private: controller::Pid *pids[GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
+ private: Pid *pids[GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
// number of joints in this array
private: int num_joints;
@@ -115,10 +115,10 @@
private: HingeJoint *finger_tip_r_joint [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
// assign pid for each finger for PD_CONTROL
- private: controller::Pid *finger_l_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
- private: controller::Pid *finger_tip_l_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
- private: controller::Pid *finger_r_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
- private: controller::Pid *finger_tip_r_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
+ private: Pid *finger_l_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
+ private: Pid *finger_tip_l_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
+ private: Pid *finger_r_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
+ private: Pid *finger_tip_r_pids [GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
// get name of each child, e.g. front_left_caster_steer
std::string actarrayName[GAZEBO_PR2ARRAY_MAX_NUM_ACTUATORS];
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Pr2_Actarray.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Pr2_Actarray.cc 2008-09-02 23:34:45 UTC (rev 3880)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Pr2_Actarray.cc 2008-09-02 23:44:37 UTC (rev 3881)
@@ -44,7 +44,6 @@
using namespace gazebo;
using namespace PR2;
-using namespace controller;
//GZ_REGISTER_STATIC_CONTROLLER("pr2_actarray", Pr2_Actarray);
Modified: pkg/trunk/mechanism/mechanism_model/include/mechanism_model/pid.h
===================================================================
--- pkg/trunk/mechanism/mechanism_model/include/mechanism_model/pid.h 2008-09-02 23:34:45 UTC (rev 3880)
+++ pkg/trunk/mechanism/mechanism_model/include/mechanism_model/pid.h 2008-09-02 23:44:37 UTC (rev 3881)
@@ -65,8 +65,6 @@
*/
/***************************************************/
class TiXmlElement;
-namespace controller
-{
class Pid
{
@@ -184,5 +182,3 @@
double i_min_; /**< Minimum allowable integral term. */
double cmd_; /**< Command to send. */
};
-
-}
Modified: pkg/trunk/mechanism/mechanism_model/src/pid.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_model/src/pid.cpp 2008-09-02 23:34:45 UTC (rev 3880)
+++ pkg/trunk/mechanism/mechanism_model/src/pid.cpp 2008-09-02 23:44:37 UTC (rev 3881)
@@ -34,8 +34,6 @@
#include "mechanism_model/pid.h"
#include "tinyxml/tinyxml.h"
-using namespace controller;
-
Pid::Pid(double P, double I, double D, double I1, double I2) :
p_gain_(P), i_gain_(I), d_gain_(D), i_max_(I1), i_min_(I2)
{
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <stu...@us...> - 2008-09-02 23:46:02
|
Revision: 3882
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3882&view=rev
Author: stuglaser
Date: 2008-09-02 23:46:04 +0000 (Tue, 02 Sep 2008)
Log Message:
-----------
The gripper transmission associates the single gripper motor with all the joints.
Modified Paths:
--------------
pkg/trunk/mechanism/mechanism_model/CMakeLists.txt
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/transmission.h
pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml
Added Paths:
-----------
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/gripper_transmission.h
pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp
Modified: pkg/trunk/mechanism/mechanism_model/CMakeLists.txt
===================================================================
--- pkg/trunk/mechanism/mechanism_model/CMakeLists.txt 2008-09-02 23:44:37 UTC (rev 3881)
+++ pkg/trunk/mechanism/mechanism_model/CMakeLists.txt 2008-09-02 23:46:04 UTC (rev 3882)
@@ -1,4 +1,4 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
rospack(mechanism_model)
-rospack_add_library(mechanism_model src/simple_transmission.cpp src/joint.cpp src/robot.cpp src/link.cpp src/chain.cpp src/pid.cpp)
+rospack_add_library(mechanism_model src/simple_transmission.cpp src/gripper_transmission.cpp src/joint.cpp src/robot.cpp src/link.cpp src/chain.cpp src/pid.cpp)
Added: pkg/trunk/mechanism/mechanism_model/include/mechanism_model/gripper_transmission.h
===================================================================
--- pkg/trunk/mechanism/mechanism_model/include/mechanism_model/gripper_transmission.h (rev 0)
+++ pkg/trunk/mechanism/mechanism_model/include/mechanism_model/gripper_transmission.h 2008-09-02 23:46:04 UTC (rev 3882)
@@ -0,0 +1,81 @@
+/*
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage, Inc. nor the names of its
+ * contributors may 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.
+ */
+
+/*
+ * <transmission type="GripperTransmission" name="gripper_l_transmission">
+ * <actuator name="gripper_l_motor" />
+ * <joint name="gripper_l_upper1_joint" reduction="4" />
+ * <joint name="gripper_l_lower1_joint" reduction="-4" />
+ * <joint name="gripper_l_upper2_joint" reduction="-8" />
+ * <joint name="gripper_l_lower2_joint" reduction="8" />
+ * <motorTorqueConstant>1</motorTorqueConstant>
+ * <pulsesPerRevolution>90000</pulsesPerRevolution>
+ * <!-- GripTransmission uses a PID controller to keep the joint angles aligned in Gazebo -->
+ * <pid p="1.0" i="2.0" d="3.0" iClamp="2.0" /> <!-- Only needed for Gazebo -->
+ * </transmission>
+ *
+ * Author: Stuart Glaser
+ */
+
+#ifndef GRIPPER_TRANSMISSION_H
+#define GRIPPER_TRANSMISSION_H
+
+#include <vector>
+#include "tinyxml/tinyxml.h"
+#include "mechanism_model/transmission.h"
+#include "mechanism_model/robot.h"
+#include "mechanism_model/pid.h"
+
+namespace mechanism {
+
+class GripperTransmission : public Transmission
+{
+public:
+ GripperTransmission() {}
+ virtual ~GripperTransmission() {}
+
+ bool initXml(TiXmlElement *config, Robot *robot);
+
+ void propagatePosition();
+ void propagatePositionBackwards();
+ void propagateEffort();
+ void propagateEffortBackwards();
+
+ Actuator *actuator_;
+ std::vector<Joint*> joints_;
+ std::vector<double> reductions_; // Mechanical reduction for each joint
+ std::vector<Pid> pids_; // For keeping the joint angles aligned in Gazebo
+
+ double motor_torque_constant_;
+ double pulses_per_revolution_;
+};
+
+} // namespace mechanism
+
+#endif
Modified: pkg/trunk/mechanism/mechanism_model/include/mechanism_model/transmission.h
===================================================================
--- pkg/trunk/mechanism/mechanism_model/include/mechanism_model/transmission.h 2008-09-02 23:44:37 UTC (rev 3881)
+++ pkg/trunk/mechanism/mechanism_model/include/mechanism_model/transmission.h 2008-09-02 23:46:04 UTC (rev 3882)
@@ -64,7 +64,7 @@
virtual bool initXml(TiXmlElement *config, Robot *robot) = 0;
// another way to initialize simple transmission
- virtual void initTransmission(std::string transmission_name,std::string joint_name,std::string actuator_name,double mechanical_reduction,double motor_torque_constant,double pulses_per_revolution, Robot *robot) = 0;
+ virtual void initTransmission(std::string transmission_name,std::string joint_name,std::string actuator_name,double mechanical_reduction,double motor_torque_constant,double pulses_per_revolution, Robot *robot) {}
// Uses encoder data to fill out joint position and velocities
virtual void propagatePosition() = 0;
Added: pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp (rev 0)
+++ pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp 2008-09-02 23:46:04 UTC (rev 3882)
@@ -0,0 +1,149 @@
+/*
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage, Inc. nor the names of its
+ * contributors may 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: Stuart Glaser
+ */
+
+#include "mechanism_model/gripper_transmission.h"
+#include <algorithm>
+#include <numeric>
+
+namespace mechanism {
+
+ROS_REGISTER_TRANSMISSION(GripperTransmission)
+
+bool GripperTransmission::initXml(TiXmlElement *config, Robot *robot)
+{
+ TiXmlElement *ael = config->FirstChildElement("actuator");
+ const char *actuator_name = ael ? ael->Attribute("name") : NULL;
+ actuator_ = actuator_name ? robot->getActuator(actuator_name) : NULL;
+ if (!actuator_)
+ {
+ fprintf(stderr, "GripperTransmission could not find actuator named \"%s\"\n", actuator_name);
+ return false;
+ }
+
+ for (TiXmlElement *j = config->FirstChildElement("joint"); j; j = j->NextSiblingElement("joint"))
+ {
+ const char *joint_name = j->Attribute("name");
+ Joint* joint = joint_name ? robot->getJoint(joint_name) : NULL;
+ if (!joint)
+ {
+ fprintf(stderr, "GripperTransmission could not find joint named \"%s\"\n", joint_name);
+ return false;
+ }
+ joints_.push_back(joint);
+
+ const char *joint_red = j->Attribute("reduction");
+ if (!joint_red)
+ {
+ fprintf(stderr, "GripperTransmission's joint \"%s\" was not given a reduction.\n", joint_name);
+ return false;
+ }
+ reductions_.push_back(atof(joint_red));
+ }
+
+ pids_.resize(joints_.size());
+ TiXmlElement *pel = config->FirstChildElement("pid");
+ if (pel)
+ {
+ Pid pid;
+ pid.initXml(pel);
+ for (unsigned int i = 0; i < pids_.size(); ++i)
+ pids_[i] = pid;
+ }
+
+ motor_torque_constant_ = atof(config->FirstChildElement("motorTorqueConstant")->GetText()),
+ pulses_per_revolution_ = atof(config->FirstChildElement("pulsesPerRevolution")->GetText());
+
+ return true;
+}
+
+void GripperTransmission::propagatePosition()
+{
+ assert(actuator_);
+ for (unsigned int i = 0; i < joints_.size(); ++i)
+ {
+ double mr = reductions_[i];
+ joints_[i]->position_ = actuator_->state_.encoder_count_ * 2 * M_PI / (mr * pulses_per_revolution_);
+ joints_[i]->velocity_ = actuator_->state_.encoder_velocity_ * 2 * M_PI / (mr * pulses_per_revolution_);
+ joints_[i]->applied_effort_ = actuator_->state_.last_measured_current_ * mr * motor_torque_constant_;
+ }
+}
+
+void GripperTransmission::propagatePositionBackwards()
+{
+ double mean_encoder = 0.0;
+ double mean_encoder_v = 0.0;
+ double mean_current = 0.0;
+ for (unsigned int i = 0; i < joints_.size(); ++i)
+ {
+ double mr = reductions_[i];
+ mean_encoder += joints_[i]->position_ * mr * pulses_per_revolution_ / (2 * M_PI);
+ mean_encoder_v += joints_[i]->velocity_ * mr * pulses_per_revolution_ / (2 * M_PI);
+ mean_current += joints_[i]->applied_effort_ / (mr * motor_torque_constant_);
+ }
+ actuator_->state_.encoder_count_ = mean_encoder / joints_.size();
+ actuator_->state_.encoder_velocity_ = mean_encoder_v / joints_.size();
+ actuator_->state_.last_measured_current_ = mean_current / joints_.size();
+}
+
+void GripperTransmission::propagateEffort()
+{
+ double strongest = 0.0;
+ for (unsigned int i = 0; i < joints_.size(); ++i)
+ {
+ if (fabs(joints_[i]->commanded_effort_ / (reductions_[i])) > fabs(strongest))
+ strongest = joints_[i]->commanded_effort_ / (reductions_[i] * motor_torque_constant_);
+ }
+ actuator_->command_.current_ = strongest;
+}
+
+void GripperTransmission::propagateEffortBackwards()
+{
+ std::vector<double> scaled_positions(joints_.size());
+ for (unsigned int i = 0; i < joints_.size(); ++i)
+ scaled_positions[i] = joints_[i]->position_ * reductions_[i];
+
+ double mean = std::accumulate(scaled_positions.begin(), scaled_positions.end(), 0.0)
+ / scaled_positions.size();
+
+ for (unsigned int i = 0; i < joints_.size(); ++i)
+ {
+ double err = scaled_positions[i] - mean;
+ double pid_effort = pids_[i].updatePid(err, 0.001);
+
+ joints_[i]->commanded_effort_ =
+ pid_effort / reductions_[i] +
+ actuator_->command_.current_ * reductions_[i] * motor_torque_constant_;
+ }
+}
+
+} // namespace mechanism
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml 2008-09-02 23:44:37 UTC (rev 3881)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/transmissions.xml 2008-09-02 23:46:04 UTC (rev 3882)
@@ -151,10 +151,13 @@
</transmission>
<!-- fingers share a single motor -->
- <transmission type="SimpleTransmission" name="gripper_left_trans">
+ <transmission type="GripperTransmission" name="gripper_left_trans">
<actuator name="gripper_left_motor" />
- <joint name="gripper_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
+ <joint name="finger_r_left_joint" reduction="-1.0" />
+ <joint name="finger_tip_r_left_joint" reduction="1.0" />
+ <joint name="finger_l_left_joint" reduction="1.0" />
+ <joint name="finger_tip_l_left_joint" reduction="-1.0" />
+ <pid p="0.10" i="0.0" d="0.005" iClamp="0.5" />
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
@@ -218,10 +221,13 @@
</transmission>
<!-- fingers share a single motor -->
- <transmission type="SimpleTransmission" name="gripper_right_trans">
+ <transmission type="GripperTransmission" name="gripper_right_trans">
<actuator name="gripper_right_motor" />
- <joint name="gripper_right_joint" />
- <mechanicalReduction>1</mechanicalReduction>
+ <joint name="finger_r_right_joint" reduction="-1.0" />
+ <joint name="finger_tip_r_right_joint" reduction="1.0" />
+ <joint name="finger_l_right_joint" reduction="1.0" />
+ <joint name="finger_tip_l_right_joint" reduction="-1.0" />
+ <pid p="0.10" i="0.0" d="0.005" iClamp="0.5" />
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jl...@us...> - 2008-09-03 01:08:11
|
Revision: 3884
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3884&view=rev
Author: jleibs
Date: 2008-09-03 01:08:17 +0000 (Wed, 03 Sep 2008)
Log Message:
-----------
Slightly refactoring self test to make usage more straightforward.
Modified Paths:
--------------
pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
pkg/trunk/drivers/imu/imu_node/imu_node.cc
pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
Modified: pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
===================================================================
--- pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2008-09-03 00:47:02 UTC (rev 3883)
+++ pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2008-09-03 01:08:17 UTC (rev 3884)
@@ -30,8 +30,6 @@
#include <stdio.h>
#include <iostream>
-#include <pthread.h>
-
#include "ros/node.h"
#include "std_msgs/Image.h"
#include "std_srvs/PolledImage.h"
@@ -64,8 +62,6 @@
param("~host", axis_host, string("192.168.0.90"));
printf("axis_cam host set to [%s]\n", axis_host.c_str());
- self_test_.lock();
-
self_test_.addTest(&Axis_cam_node::checkImage);
self_test_.addTest(&Axis_cam_node::checkMac);
@@ -73,8 +69,6 @@
next_time = ros::Time::now();
count_ = 0;
-
- self_test_.unlock();
}
virtual ~Axis_cam_node()
@@ -94,15 +88,12 @@
bool take_and_send_image()
{
- self_test_.lock();
uint8_t *jpeg;
uint32_t jpeg_size;
if (cam->get_jpeg(&jpeg, &jpeg_size))
{
log(ros::ERROR, "woah! AxisCam::get_jpeg returned an error");
- self_test_.unlock();
- sched_yield();
return false;
}
@@ -115,10 +106,6 @@
publish("image", image);
- self_test_.unlock();
-
- sched_yield();
-
return true;
}
@@ -143,6 +130,7 @@
param("~host", axis_host, string("192.168.0.90"));
cam->set_host(axis_host);
}
+ self_test_.checkTest();
}
return true;
}
Modified: pkg/trunk/drivers/imu/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-09-03 00:47:02 UTC (rev 3883)
+++ pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-09-03 01:08:17 UTC (rev 3884)
@@ -74,14 +74,12 @@
#include "3dmgx2.h"
-#include <ros/node.h>
-#include <std_msgs/ImuData.h>
-#include <std_msgs/EulerAngles.h>
+#include "ros/node.h"
#include "ros/time.h"
-
#include "self_test/self_test.h"
-#include <pthread.h>
+#include "std_msgs/ImuData.h"
+#include "std_msgs/EulerAngles.h"
using namespace std;
@@ -148,8 +146,6 @@
{
stop();
- self_test_.lock();
-
try
{
imu.open_port(port.c_str());
@@ -170,20 +166,16 @@
} catch (MS_3DMGX2::exception& e) {
printf("Exception thrown while starting imu.\n %s\n", e.what());
- self_test_.unlock();
return -1;
}
next_time = ros::Time::now();
- self_test_.unlock();
return(0);
}
int stop()
{
- self_test_.lock();
-
if(running)
{
try
@@ -195,15 +187,11 @@
running = false;
}
- self_test_.unlock();
return(0);
}
int publish_datum()
{
-
- self_test_.lock();
-
try
{
uint64_t time;
@@ -247,14 +235,12 @@
default:
printf("Unhandled message type!\n");
- self_test_.unlock();
return -1;
}
} catch (MS_3DMGX2::exception& e) {
printf("Exception thrown while trying to get the reading.\n%s\n", e.what());
- self_test_.unlock();
return -1;
}
@@ -266,8 +252,6 @@
next_time = next_time + ros::Duration(1,0);
}
- self_test_.unlock();
- sched_yield();
return(0);
}
@@ -281,9 +265,11 @@
while(ok()) {
if(publish_datum() < 0)
break;
+ self_test_.checkTest();
}
} else {
usleep(1000000);
+ self_test_.checkTest();
}
}
Modified: pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc
===================================================================
--- pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-09-03 00:47:02 UTC (rev 3883)
+++ pkg/trunk/drivers/laser/hokuyourg_player/hokuyourg_player.cc 2008-09-03 01:08:17 UTC (rev 3884)
@@ -99,7 +99,6 @@
#include <iostream>
#include <sstream>
#include <iomanip>
-#include <pthread.h>
#include "ros/node.h"
#include "ros/time.h"
@@ -188,7 +187,6 @@
{
stop();
- self_test_.lock();
try
{
urg.open(port.c_str());
@@ -205,7 +203,6 @@
if (status != 0) {
printf("Failed to request scans from URG. Status: %d.\n", status);
- self_test_.unlock();
return -1;
}
@@ -213,19 +210,16 @@
} catch (URG::exception& e) {
printf("Exception thrown while starting urg.\n%s\n", e.what());
- self_test_.unlock();
return -1;
}
next_time = ros::Time::now();
- self_test_.unlock();
return(0);
}
int stop()
{
- self_test_.lock();
if(running)
{
try
@@ -237,13 +231,11 @@
running = false;
}
- self_test_.unlock();
return 0;
}
int publish_scan()
{
- self_test_.lock();
try
{
int status = urg.service_scan(&scan);
@@ -255,12 +247,10 @@
}
} catch (URG::corrupted_data_exception &e) {
printf("CORRUPTED DATA\n");
- self_test_.unlock();
return 0;
} catch (URG::exception& e) {
printf("Exception thrown while trying to get scan.\n%s\n", e.what());
running = false; //If we're here, we are no longer running
- self_test_.unlock();
return -1;
}
@@ -292,8 +282,6 @@
next_time = next_time + ros::Duration(1,0);
}
- self_test_.unlock();
- sched_yield();
return(0);
}
@@ -308,9 +296,11 @@
while(ok()) {
if(publish_scan() < 0)
break;
+ self_test_.checkTest();
}
} else {
usleep(1000000);
+ self_test_.checkTest();
}
}
Modified: pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
===================================================================
--- pkg/trunk/hardware_test/self_test/include/self_test/self_test.h 2008-09-03 00:47:02 UTC (rev 3883)
+++ pkg/trunk/hardware_test/self_test/include/self_test/self_test.h 2008-09-03 01:08:17 UTC (rev 3884)
@@ -40,18 +40,21 @@
#include <string>
#include "ros/node.h"
-#include "rosthread/mutex.h"
+#include "rosthread/condition.h"
#include "robot_msgs/DiagnosticStatus.h"
#include "robot_srvs/SelfTest.h"
+
+
template <class T>
class SelfTest
{
private:
T* node_;
- ros::thread::mutex testing_mutex;
+ ros::thread::condition testing_condition;
+ ros::thread::condition done_testing_condition;
std::string id_;
@@ -60,11 +63,21 @@
void (T::*pretest_)();
void (T::*posttest_)();
+ int count;
+
+ bool waiting;
+ bool ready;
+ bool done;
+
public:
SelfTest(T* node) : node_(node), pretest_(NULL), posttest_(NULL)
{
node_->advertise_service("~self_test", &SelfTest::doTest, this);
+ count = 0;
+ waiting = false;
+ ready = false;
+ done = false;
}
void addTest(void (T::*f)(robot_msgs::DiagnosticStatus&))
@@ -82,14 +95,24 @@
posttest_ = f;
}
- void lock()
+ void checkTest()
{
- testing_mutex.lock();
- }
+ testing_condition.lock();
+ if (waiting)
+ {
+ ready = true;
+ testing_condition.signal();
+ testing_condition.unlock();
- void unlock()
- {
- testing_mutex.unlock();
+ done_testing_condition.lock();
+ done = false;
+ while (!done)
+ done_testing_condition.wait();
+ done_testing_condition.unlock();
+ } else {
+ testing_condition.unlock();
+ }
+ sched_yield();
}
void setID(std::string id)
@@ -100,8 +123,28 @@
bool doTest(robot_srvs::SelfTest::request &req,
robot_srvs::SelfTest::response &res)
{
- lock();
+ testing_condition.lock();
+ waiting = true;
+ ready = false;
+
+ while (!ready)
+ {
+ if (!testing_condition.timed_wait(5))
+ {
+ printf("Timed out waiting to run self test.\n");
+ waiting = false;
+ testing_condition.unlock();
+ return false;
+ }
+ }
+
+ testing_condition.unlock();
+
+ bool retval = false;
+
+ printf("Begining test.\n");
+
if (node_->ok())
{
@@ -139,6 +182,9 @@
status_vec.push_back(status);
}
+ waiting = false;
+ testing_condition.unlock();
+
//One of the test calls should use setID
res.id = id_;
@@ -160,13 +206,17 @@
printf("Self test completed\n");
- unlock();
+ retval = true;
- return true;
+ }
- } else {
- return false;
- }
+ done_testing_condition.lock();
+ done = true;
+ done_testing_condition.signal();
+ done_testing_condition.unlock();
+
+ return retval;
+
}
};
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2008-09-03 17:54:26
|
Revision: 3893
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3893&view=rev
Author: isucan
Date: 2008-09-03 17:54:28 +0000 (Wed, 03 Sep 2008)
Log Message:
-----------
moving temporary planning world viewer to deprecated. ogre_visualizer now contains the needed functionality
Added Paths:
-----------
pkg/trunk/deprecated/planning_world_viewer/
pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt
pkg/trunk/deprecated/planning_world_viewer/Makefile
pkg/trunk/deprecated/planning_world_viewer/manifest.xml
pkg/trunk/deprecated/planning_world_viewer/res/
pkg/trunk/deprecated/planning_world_viewer/src/
Removed Paths:
-------------
pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt
pkg/trunk/deprecated/planning_world_viewer/Makefile
pkg/trunk/deprecated/planning_world_viewer/manifest.xml
pkg/trunk/deprecated/planning_world_viewer/res/
pkg/trunk/deprecated/planning_world_viewer/src/
pkg/trunk/motion_planning/planning_world_viewer/
Deleted: pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/planning_world_viewer/CMakeLists.txt 2008-09-03 17:01:35 UTC (rev 3888)
+++ pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt 2008-09-03 17:54:28 UTC (rev 3893)
@@ -1,4 +0,0 @@
-cmake_minimum_required(VERSION 2.6)
-include(rosbuild)
-rospack(planning_world_viewer)
-rospack_add_executable(planning_world_viewer src/planning_world_viewer.cpp)
Copied: pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt (from rev 3892, pkg/trunk/motion_planning/planning_world_viewer/CMakeLists.txt)
===================================================================
--- pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt (rev 0)
+++ pkg/trunk/deprecated/planning_world_viewer/CMakeLists.txt 2008-09-03 17:54:28 UTC (rev 3893)
@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(planning_world_viewer)
+rospack_add_executable(planning_world_viewer src/planning_world_viewer.cpp)
Deleted: pkg/trunk/deprecated/planning_world_viewer/Makefile
===================================================================
--- pkg/trunk/motion_planning/planning_world_viewer/Makefile 2008-09-03 17:01:35 UTC (rev 3888)
+++ pkg/trunk/deprecated/planning_world_viewer/Makefile 2008-09-03 17:54:28 UTC (rev 3893)
@@ -1 +0,0 @@
-include $(shell rospack find mk)/cmake.mk
Copied: pkg/trunk/deprecated/planning_world_viewer/Makefile (from rev 3892, pkg/trunk/motion_planning/planning_world_viewer/Makefile)
===================================================================
--- pkg/trunk/deprecated/planning_world_viewer/Makefile (rev 0)
+++ pkg/trunk/deprecated/planning_world_viewer/Makefile 2008-09-03 17:54:28 UTC (rev 3893)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Deleted: pkg/trunk/deprecated/planning_world_viewer/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/planning_world_viewer/manifest.xml 2008-09-03 17:01:35 UTC (rev 3888)
+++ pkg/trunk/deprecated/planning_world_viewer/manifest.xml 2008-09-03 17:54:28 UTC (rev 3893)
@@ -1,11 +0,0 @@
-<package>
- <description>Kinematic motion planning using OMPL</description>
- <author>Ioan A. Sucan</author>
- <license>BSD</license>
- <depend package="roscpp" />
- <depend package="robot_msgs" />
- <depend package="robot_srvs" />
- <depend package="rosthread" />
- <depend package="planning_node_util" />
- <depend package="display_ode_spaces" />
-</package>
Copied: pkg/trunk/deprecated/planning_world_viewer/manifest.xml (from rev 3892, pkg/trunk/motion_planning/planning_world_viewer/manifest.xml)
===================================================================
--- pkg/trunk/deprecated/planning_world_viewer/manifest.xml (rev 0)
+++ pkg/trunk/deprecated/planning_world_viewer/manifest.xml 2008-09-03 17:54:28 UTC (rev 3893)
@@ -0,0 +1,11 @@
+<package>
+ <description>Kinematic motion planning using OMPL</description>
+ <author>Ioan A. Sucan</author>
+ <license>BSD</license>
+ <depend package="roscpp" />
+ <depend package="robot_msgs" />
+ <depend package="robot_srvs" />
+ <depend package="rosthread" />
+ <depend package="planning_node_util" />
+ <depend package="display_ode_spaces" />
+</package>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <stu...@us...> - 2008-09-04 21:54:11
|
Revision: 3954
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3954&view=rev
Author: stuglaser
Date: 2008-09-04 21:54:19 +0000 (Thu, 04 Sep 2008)
Log Message:
-----------
Separated robot state from the robot model and ported all the controllers.
Modified Paths:
--------------
pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_effort_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_pd_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_position_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/ramp_effort_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/sine_sweep_controller.h
pkg/trunk/controllers/generic_controllers/src/joint_effort_controller.cpp
pkg/trunk/controllers/generic_controllers/src/joint_pd_controller.cpp
pkg/trunk/controllers/generic_controllers/src/joint_position_controller.cpp
pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp
pkg/trunk/controllers/generic_controllers/src/ramp_effort_controller.cpp
pkg/trunk/controllers/generic_controllers/src/sine_sweep_controller.cpp
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/arm_position_controller.h
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/arm_velocity_controller.h
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/laser_scanner_controller.h
pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp
pkg/trunk/controllers/pr2_controllers/src/arm_velocity_controller.cpp
pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
pkg/trunk/controllers/pr2_controllers/src/laser_scanner_controller.cpp
pkg/trunk/controllers/pr2_controllers/test/test_base_controller.cpp
pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/include/motor_qualification_controllers/motor_test1.h
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_actuators.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_actuators.cpp
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/gripper_transmission.h
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/joint.h
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/link.h
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/robot.h
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/simple_transmission.h
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/transmission.h
pkg/trunk/mechanism/mechanism_model/src/chain.cpp
pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp
pkg/trunk/mechanism/mechanism_model/src/joint.cpp
pkg/trunk/mechanism/mechanism_model/src/link.cpp
pkg/trunk/mechanism/mechanism_model/src/robot.cpp
pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -46,7 +46,6 @@
#include <mechanism_model/robot.h>
#include <tinyxml/tinyxml.h>
-//class TiXmlElement;
namespace controller
{
@@ -89,7 +88,7 @@
{
}
virtual void update(void) = 0;
- virtual bool initXml(mechanism::Robot *robot, TiXmlElement *config) = 0;
+ virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config) = 0;
};
}
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_effort_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_effort_controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_effort_controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -77,8 +77,7 @@
* \brief Functional way to initialize limits and gains.
*
*/
- void init(std::string name,mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -109,8 +108,8 @@
virtual void update();
private:
- mechanism::Joint* joint_; /**< Joint we're controlling. */
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
+ mechanism::JointState *joint_; /**< Joint we're controlling. */
+ mechanism::RobotState *robot_; /**< Pointer to robot structure. */
double command_; /**< Last commanded position. */
};
@@ -140,8 +139,7 @@
void update();
- void init(std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
// Services
bool setCommand(generic_controllers::SetCommand::request &req,
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_pd_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_pd_controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_pd_controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -44,9 +44,9 @@
Example config:
<controller type="JointPDController" name="controller_name">
- <joint name="joint_to_control">
- <pid p="1.0" i="2.0" d="3.0" iClamp="4.0" />
- </joint>
+ <joint name="joint_to_control">
+ <pid p="1.0" i="2.0" d="3.0" iClamp="4.0" />
+ </joint>
</controller>
*/
/***************************************************/
@@ -88,8 +88,8 @@
* \param *joint The joint that is being controlled.
*/
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -130,22 +130,15 @@
std::string getJointName();
- private:
+ private:
- mechanism::Joint* joint_; /**< Joint we're controlling. */
-
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
-
+ mechanism::JointState* joint_; /**< Joint we're controlling. */
+ mechanism::RobotState *robot_; /**< Pointer to robot structure. */
Pid pid_controller_; /**< Internal PID controller. */
-
double last_time_; /**< Last time stamp of update. */
-
double command_; /**< Last commanded position. */
-
double command_dot_;
-
double command_t_; /**< Last commanded position. */
-
double command_dot_t_;
/*!
@@ -185,8 +178,8 @@
void update();
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
// Services
bool setPDCommand(generic_controllers::SetPDCommand::request &req,
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_position_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_position_controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_position_controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -87,8 +87,7 @@
* \param time The current hardware time.
* \param *joint The joint that is being controlled.
*/
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -125,8 +124,8 @@
std::string getJointName();
private:
- mechanism::Joint* joint_; /**< Joint we're controlling. */
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
+ mechanism::JointState *joint_state_; /**< Joint we're controlling. */
+ mechanism::RobotState *robot_; /**< Pointer to robot structure. */
Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
double command_; /**< Last commanded position. */
@@ -160,8 +159,7 @@
void update();
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
// Services
bool setCommand(generic_controllers::SetCommand::request &req,
@@ -173,7 +171,7 @@
double getMeasuredPosition();
bool getActual(generic_controllers::GetActual::request &req,
- generic_controllers::GetActual::response &resp);
+ generic_controllers::GetActual::response &resp);
private:
JointPositionController *c_;
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -88,7 +88,7 @@
*/
void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -125,8 +125,8 @@
std::string getJointName();
private:
- mechanism::Joint* joint_; /**< Joint we're controlling. */
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
+ mechanism::JointState *joint_state_;
+ mechanism::RobotState *robot_; /**< Pointer to robot structure. */
Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
double command_; /**< Last commanded position. */
@@ -163,8 +163,7 @@
void update();
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
// Services
bool setCommand(generic_controllers::SetCommand::request &req,
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/ramp_effort_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/ramp_effort_controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/ramp_effort_controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -69,18 +69,9 @@
*/
~RampEffortController();
- /*!
- * \brief Functional way to initialize.
- * \param input_start The start value of the ramp.
- * \param input_end The end value of the ramp.
- * \param duration The duration in seconds from start to finish.
- * \param time The current hardware time.
- * \param *joint The joint that is being controlled.
- */
- void init(double input_start, double input_end, double duration, double time,std::string name,mechanism::Robot *robot);
+ void init(double input_start, double input_end, double duration, double time,std::string name,mechanism::RobotState *robot);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
-
/*!
* \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
*/
@@ -108,8 +99,8 @@
virtual void update();
private:
- mechanism::Joint* joint_; /**< Joint we're controlling. */
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
+ mechanism::JointState *joint_state_; /**< Joint we're controlling. */
+ mechanism::RobotState *robot_; /**< Pointer to robot structure. */
double input_start_; /**< Begining of the ramp. */
double input_end_; /**< End of the ramp. */
double duration_; /**< Duration of the ramp. */
@@ -143,8 +134,7 @@
void update();
- void init(double input_start, double input_end, double duration, double time,std::string name,mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
bool getActual(generic_controllers::GetActual::request &req,
generic_controllers::GetActual::response &resp);
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/sine_sweep_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/sine_sweep_controller.h 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/sine_sweep_controller.h 2008-09-04 21:54:19 UTC (rev 3954)
@@ -79,9 +79,9 @@
* \param time The current hardware time.
* \param *robot The robot that is being controlled.
*/
- void init(double start_freq, double end_freq, double duration, double amplitude, double time,std::string name,mechanism::Robot *robot);
+ void init(double start_freq, double end_freq, double duration, double amplitude, double time,std::string name,mechanism::RobotState *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
/*!
* \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
@@ -106,8 +106,8 @@
virtual void update();
private:
- mechanism::Joint* joint_; /**< Joint we're controlling. */
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
+ mechanism::JointState *joint_state_; /**< Joint we're controlling. */
+ mechanism::RobotState *robot_; /**< Pointer to robot structure. */
double start_freq_; /**< Begining of the sweep. */
double end_freq_; /**< End of the sweep. */
double amplitude_; /**< Amplitude of the sweep. */
@@ -146,8 +146,7 @@
void update();
- void init(double start_freq, double end_freq, double duration, double amplitude, double time,std::string name,mechanism::Robot *robot);
- bool initXml(mechanism::Robot *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
private:
SineSweepController *c_;
Modified: pkg/trunk/controllers/generic_controllers/src/joint_effort_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/joint_effort_controller.cpp 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/src/joint_effort_controller.cpp 2008-09-04 21:54:19 UTC (rev 3954)
@@ -50,16 +50,8 @@
{
}
-void JointEffortController::init(std::string name,mechanism::Robot *robot)
+bool JointEffortController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
- robot_ = robot;
- joint_ = robot->getJoint(name);
-
- command_= 0;
-}
-
-bool JointEffortController::initXml(mechanism::Robot *robot, TiXmlElement *config)
-{
assert(robot);
robot_ = robot;
@@ -71,7 +63,7 @@
}
const char *joint_name = j->Attribute("name");
- joint_ = joint_name ? robot->getJoint(joint_name) : NULL;
+ joint_ = joint_name ? robot->getJointState(joint_name) : NULL;
if (!joint_)
{
fprintf(stderr, "JointVelocityController could not find joint named \"%s\"\n", joint_name);
@@ -145,21 +137,10 @@
return true;
}
-void JointEffortControllerNode::init(std::string name, mechanism::Robot *robot)
+bool JointEffortControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
- string prefix = name;
- c_->init(name, robot);
- node->advertise_service(prefix + "/set_command", &JointEffortControllerNode::setCommand, this);
- node->advertise_service(prefix + "/get_actual", &JointEffortControllerNode::getActual, this);
-}
-
-
-bool JointEffortControllerNode::initXml(mechanism::Robot *robot, TiXmlElement *config)
-{
- ros::node *node = ros::node::instance();
-
std::string topic = config->Attribute("topic") ? config->Attribute("topic") : "";
if (topic == "")
{
Modified: pkg/trunk/controllers/generic_controllers/src/joint_pd_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/joint_pd_controller.cpp 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/src/joint_pd_controller.cpp 2008-09-04 21:54:19 UTC (rev 3954)
@@ -57,10 +57,10 @@
{
}
-void JointPDController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
+void JointPDController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot)
{
robot_ = robot;
- joint_ = robot->getJoint(name);
+ joint_ = robot->getJointState(name);
pid_controller_.initPid(p_gain, i_gain, d_gain, windup, -windup);
command_= 0;
@@ -69,7 +69,7 @@
}
-bool JointPDController::initXml(mechanism::Robot *robot, TiXmlElement *config)
+bool JointPDController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
assert(robot);
robot_ = robot;
@@ -83,7 +83,7 @@
}
const char *joint_name = j->Attribute("name");
- joint_ = joint_name ? robot->getJoint(joint_name) : NULL;
+ joint_ = joint_name ? robot->getJointState(joint_name) : NULL;
if (!joint_)
{
fprintf(stderr, "JointPDController could not find joint named \"%s\"\n", joint_name);
@@ -137,7 +137,7 @@
std::string JointPDController::getJointName()
{
- return(joint_->name_);
+ return(joint_->joint_->name_);
}
void JointPDController::update()
@@ -218,7 +218,7 @@
}
-void JointPDControllerNode::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
+void JointPDControllerNode::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot)
{
ros::node *node = ros::node::instance();
string prefix = name;
@@ -228,7 +228,7 @@
node->advertise_service(prefix + "/get_actual", &JointPDControllerNode::getPDActual, this);
}
-bool JointPDControllerNode::initXml(mechanism::Robot *robot, TiXmlElement *config)
+bool JointPDControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
Modified: pkg/trunk/controllers/generic_controllers/src/joint_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/joint_position_controller.cpp 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/src/joint_position_controller.cpp 2008-09-04 21:54:19 UTC (rev 3954)
@@ -40,10 +40,8 @@
ROS_REGISTER_CONTROLLER(JointPositionController)
JointPositionController::JointPositionController()
+: joint_state_(NULL), robot_(NULL)
{
- robot_ = NULL;
- joint_ = NULL;
-
// Initialize PID class
pid_controller_.initPid(0, 0, 0, 0, 0);
command_ = 0;
@@ -54,18 +52,8 @@
{
}
-void JointPositionController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
+bool JointPositionController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
- robot_ = robot;
- joint_ = robot->getJoint(name);
-
- pid_controller_.initPid(p_gain, i_gain, d_gain, windup, -windup);
- command_= 0;
- last_time_= time;
-}
-
-bool JointPositionController::initXml(mechanism::Robot *robot, TiXmlElement *config)
-{
assert(robot);
robot_ = robot;
last_time_ = robot->hw_->current_time_;
@@ -78,12 +66,13 @@
}
const char *joint_name = j->Attribute("name");
- joint_ = joint_name ? robot->getJoint(joint_name) : NULL;
- if (!joint_)
+ int index = joint_name ? robot->model_->getJointIndex(joint_name) : -1;
+ if (index < 0)
{
fprintf(stderr, "JointPositionController could not find joint named \"%s\"\n", joint_name);
return false;
}
+ joint_state_ = &robot->joint_states_[index];
TiXmlElement *p = j->FirstChildElement("pid");
if (p)
@@ -112,7 +101,7 @@
std::string JointPositionController::getJointName()
{
- return(joint_->name_);
+ return joint_state_->joint_->name_;
}
// Return the current position command
@@ -124,7 +113,7 @@
// Return the measured joint position
double JointPositionController::getMeasuredPosition()
{
- return joint_->position_;
+ return joint_state_->position_;
}
double JointPositionController::getTime()
@@ -138,18 +127,19 @@
double error(0);
double time = robot_->hw_->current_time_;
- if(joint_)
+ if(joint_state_->joint_)
{
- if(joint_->type_ == mechanism::JOINT_ROTARY || joint_->type_ == mechanism::JOINT_CONTINUOUS)
+ if(joint_state_->joint_->type_ == mechanism::JOINT_ROTARY ||
+ joint_state_->joint_->type_ == mechanism::JOINT_CONTINUOUS)
{
- error = math_utils::shortest_angular_distance(command_, joint_->position_);
+ error = math_utils::shortest_angular_distance(command_, joint_state_->position_);
}
else
{
- error = joint_->position_ - command_;
+ error = joint_state_->position_ - command_;
}
- joint_->commanded_effort_ = pid_controller_.updatePid(error, time - last_time_);
+ joint_state_->commanded_effort_ = pid_controller_.updatePid(error, time - last_time_);
}
last_time_ = time;
}
@@ -207,19 +197,10 @@
return c_->getMeasuredPosition();
}
-void JointPositionControllerNode::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
+bool JointPositionControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
- string prefix = name;
-
- c_->init(p_gain, i_gain, d_gain, windup, time, name,robot);
- node->advertise_service(prefix + "/set_command", &JointPositionControllerNode::setCommand, this);
- node->advertise_service(prefix + "/get_actual", &JointPositionControllerNode::getActual, this);
-}
-
-bool JointPositionControllerNode::initXml(mechanism::Robot *robot, TiXmlElement *config)
-{
- ros::node *node = ros::node::instance();
+ assert(node);
string prefix = config->Attribute("name");
std::string topic = config->Attribute("topic") ? config->Attribute("topic") : "";
Modified: pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp 2008-09-04 21:54:19 UTC (rev 3954)
@@ -41,10 +41,8 @@
ROS_REGISTER_CONTROLLER(JointVelocityController)
JointVelocityController::JointVelocityController()
+: joint_state_(NULL), robot_(NULL)
{
- robot_=NULL;
- joint_=NULL;
-
// Initialize PID class
pid_controller_.initPid(0, 0, 0, 0, 0);
command_ = 0;
@@ -55,19 +53,8 @@
{
}
-void JointVelocityController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
+bool JointVelocityController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
- robot_ = robot;
- joint_ = robot->getJoint(name);
-
- pid_controller_.initPid(p_gain, i_gain, d_gain, windup, -windup);
- command_= 0;
- last_time_= time;
-
-}
-
-bool JointVelocityController::initXml(mechanism::Robot *robot, TiXmlElement *config)
-{
assert(robot);
robot_ = robot;
last_time_ = robot->hw_->current_time_;
@@ -80,12 +67,13 @@
}
const char *joint_name = j->Attribute("name");
- joint_ = joint_name ? robot->getJoint(joint_name) : NULL;
- if (!joint_)
+ int index = joint_name ? robot->model_->getJointIndex(joint_name) : NULL;
+ if (index < 0)
{
fprintf(stderr, "JointVelocityController could not find joint named \"%s\"\n", joint_name);
return false;
}
+ joint_state_ = &robot_->joint_states_[index];
TiXmlElement *p = j->FirstChildElement("pid");
if (p)
@@ -116,12 +104,12 @@
// Return the measured joint velocity
double JointVelocityController::getMeasuredVelocity()
{
- return joint_->velocity_;
+ return joint_state_->velocity_;
}
std::string JointVelocityController::getJointName()
{
- return(joint_->name_);
+ return joint_state_->joint_->name_;
}
void JointVelocityController::update()
@@ -129,8 +117,8 @@
double error(0);
double time = robot_->hw_->current_time_;
- error = joint_->velocity_ - command_;
- joint_->commanded_effort_ = pid_controller_.updatePid(error, time - last_time_);
+ error = joint_state_->velocity_ - command_;
+ joint_state_->commanded_effort_ = pid_controller_.updatePid(error, time - last_time_);
last_time_ = time;
}
@@ -181,20 +169,10 @@
return true;
}
-void JointVelocityControllerNode::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot)
+bool JointVelocityControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
- string prefix = name;
- c_->init(p_gain, i_gain, d_gain, windup, time,name, robot);
- node->advertise_service(prefix + "/set_command", &JointVelocityControllerNode::setCommand, this);
- node->advertise_service(prefix + "/get_actual", &JointVelocityControllerNode::getActual, this);
-}
-
-bool JointVelocityControllerNode::initXml(mechanism::Robot *robot, TiXmlElement *config)
-{
- ros::node *node = ros::node::instance();
-
std::string topic = config->Attribute("topic") ? config->Attribute("topic") : "";
if (topic == "")
{
Modified: pkg/trunk/controllers/generic_controllers/src/ramp_effort_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/ramp_effort_controller.cpp 2008-09-04 21:04:47 UTC (rev 3953)
+++ pkg/trunk/controllers/generic_controllers/src/ramp_effort_controller.cpp 2008-09-04 21:54:19 UTC (rev 3954)
@@ -34,15 +34,14 @@
#include <generic_controllers/ramp_effort_controller.h>
using namespace std;
-using namespace controller;
+namespace controller {
+
ROS_REGISTER_CONTROLLER(RampEffortController)
RampEffortController::RampEffortController()
+: joint_state_(NULL), robot_(NULL)
{
- robot_ = NULL;
- joint_ = NULL;
-
input_start_ = 0;
input_end_ = 0;
duration_ = 0;
@@ -53,21 +52,21 @@
{
}
-void RampEffortController::init(double input_start, double input_end, double duration, double time,std::string name,mechanism::Robot *robot)
+void RampEffortController::init(double input_start, double input_end, double duration, double time,std::string name,mechanism::RobotState *robot)
{
robot_ = robot;
- joint_ = robot->getJoint(name);
-
-
+ int index = robot->model_->getJointIndex(name);
+ joint_state_ = &robot->joint_states_[index];
+
input_start_=input_start;
input_end_=input_end;
duration_=duration;
initial_time_=time;
}
-bool RampEffortController::initXml(mechanism::Robot *robot, TiXmlElement *config)
+bool RampEffortController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
{
-
+
TiXmlElement *j = config->FirstChildElement("joint");
if (!j)
{
@@ -76,13 +75,13 @@
}
const char *joint_name = j->Attribute("name");
- joint_ = joint_name ? robot->getJoint(joint_name) : NULL;
- if (!joint_)
+ joint_state_ = joint_name ? robot->getJointState(joint_name) : NULL;
+ if (!joint_state_)
{
fprintf(stderr, "RampEffortController could not find joint named \"%s\"\n", joint_name);
return false;
}
-
+
TiXmlElement *cd = j->FirstChildElement("controller_defaults");
if (cd)
{
@@ -99,19 +98,19 @@
// Return the current position command
double RampEffortController::getCommand()
{
- return joint_->commande...
[truncated message content] |
|
From: <rob...@us...> - 2008-09-04 23:06:26
|
Revision: 3960
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3960&view=rev
Author: rob_wheeler
Date: 2008-09-04 23:06:35 +0000 (Thu, 04 Sep 2008)
Log Message:
-----------
Move motor torque constant and pulses per revolution out of the transmission
and into the actuator. For now, the values are hard-coded. In the future
they will be read from the eeprom of the MCB.
Modified Paths:
--------------
pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp
pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h
pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg
pkg/trunk/mechanism/mechanism_control/scripts/listen.py
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/simple_transmission.h
pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp
pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp 2008-09-04 23:06:35 UTC (rev 3960)
@@ -151,7 +151,7 @@
current = current_buffer_;
for (unsigned int i = 0; i < hw_->actuators_.size(); ++i)
{
- hw_->actuators_[i]->state_.last_requested_current_ = hw_->actuators_[i]->command_.current_;
+ hw_->actuators_[i]->state_.last_requested_effort_ = hw_->actuators_[i]->command_.effort_;
slaves_[i]->truncateCurrent(hw_->actuators_[i]->command_);
slaves_[i]->convertCommand(hw_->actuators_[i]->command_, current);
current += slaves_[i]->command_size_ + slaves_[i]->status_size_;
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp 2008-09-04 23:06:35 UTC (rev 3960)
@@ -32,6 +32,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
+#include <math.h>
+
#include <ethercat_hardware/wg05.h>
#include <dll/ethercat_dll.h>
@@ -155,13 +157,19 @@
max_current_ = config_info_.absolute_current_limit_ * config_info_.nominal_current_scale_;
}
+static const double motor_torque_constant = -0.0603;
+static const int pulses_per_revolution = 1200;
+
void WG05::convertCommand(ActuatorCommand &command, unsigned char *buffer)
{
WG05Command c;
memset(&c, 0, sizeof(c));
- c.programmed_current_ = command.current_ / config_info_.nominal_current_scale_;
+ double current = command.effort_ / motor_torque_constant;
+ current = max(min(current, max_current_), -max_current_);
+
+ c.programmed_current_ = current / config_info_.nominal_current_scale_;
c.mode_ = command.enable_ ? (MODE_ENABLE | MODE_CURRENT) : MODE_OFF;
c.checksum_ = rotate_right_8(compute_checksum(&c, sizeof(c) - 1));
@@ -170,7 +178,7 @@
void WG05::truncateCurrent(ActuatorCommand &command)
{
- command.current_ = max(min(command.current_, max_current_), -max_current_);
+ //command.current_ = max(min(command.current_, max_current_), -max_current_);
}
void WG05::convertState(ActuatorState &state, unsigned char *current_buffer, unsigned char *last_buffer)
@@ -186,16 +194,18 @@
state.timestamp_ = current_status.timestamp_ / 1e+6;
state.encoder_count_ = current_status.encoder_count_;
+ state.position_ = double(current_status.encoder_count_) / pulses_per_revolution * 2 * M_PI;
state.encoder_velocity_ = double(int(current_status.encoder_count_ - last_status.encoder_count_))
/ (current_status.timestamp_ - last_status.timestamp_) * 1e+6;
+ state.velocity_ = state.encoder_velocity_ / pulses_per_revolution * 2 * M_PI;
state.calibration_reading_ = current_status.calibration_reading_ & LIMIT_SENSOR_0_STATE;
state.last_calibration_high_transition_ = current_status.last_calibration_high_transition_;
state.last_calibration_low_transition_ = current_status.last_calibration_low_transition_;
state.is_enabled_ = current_status.mode_ != MODE_OFF;
state.run_stop_hit_ = (current_status.mode_ & MODE_UNDERVOLTAGE) != 0;
- state.last_commanded_current_ = current_status.programmed_current_ * config_info_.nominal_current_scale_;
- state.last_measured_current_ = current_status.measured_current_ * config_info_.nominal_current_scale_;
+ state.last_commanded_effort_ = current_status.programmed_current_ * config_info_.nominal_current_scale_ * motor_torque_constant;
+ state.last_measured_effort_ = current_status.measured_current_ * config_info_.nominal_current_scale_ * motor_torque_constant;
state.num_encoder_errors_ = current_status.num_encoder_errors_;
state.num_communication_errors_ = 0; // TODO: communication errors are no longer reported in the process data
Modified: pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h
===================================================================
--- pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-09-04 23:06:35 UTC (rev 3960)
@@ -46,23 +46,28 @@
last_calibration_low_transition_(0),
is_enabled_(0),
run_stop_hit_(0),
- last_requested_current_(0),
- last_commanded_current_(0),
- last_measured_current_(0),
+ last_requested_effort_(0),
+ last_commanded_effort_(0),
+ last_measured_effort_(0),
num_encoder_errors_(0)
{}
+ double timestamp_;
+
int encoder_count_;
- double timestamp_;
+ double position_;
double encoder_velocity_;
+ double velocity_;
+
bool calibration_reading_;
int last_calibration_high_transition_;
int last_calibration_low_transition_;
+
bool is_enabled_;
bool run_stop_hit_;
- double last_requested_current_;
- double last_commanded_current_;
- double last_measured_current_;
+ double last_requested_effort_;
+ double last_commanded_effort_;
+ double last_measured_effort_;
int motor_voltage_;
@@ -74,10 +79,10 @@
{
public:
ActuatorCommand() :
- enable_(0), current_(0)
+ enable_(0), effort_(0)
{}
bool enable_;
- double current_;
+ double effort_;
};
class Actuator
Modified: pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg
===================================================================
--- pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/mechanism_control/msg/ActuatorState.msg 2008-09-04 23:06:35 UTC (rev 3960)
@@ -1,15 +1,17 @@
string name
int32 encoder_count
+float64 position
float64 timestamp
float64 encoder_velocity
+float64 velocity
byte calibration_reading
int32 last_calibration_high_transition
int32 last_calibration_low_transition
byte is_enabled
byte run_stop_hit
-float64 last_requested_current
-float64 last_commanded_current
-float64 last_measured_current
+float64 last_requested_effort
+float64 last_commanded_effort
+float64 last_measured_effort
int32 motor_voltage
int32 num_encoder_errors
Modified: pkg/trunk/mechanism/mechanism_control/scripts/listen.py
===================================================================
--- pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/mechanism_control/scripts/listen.py 2008-09-04 23:06:35 UTC (rev 3960)
@@ -19,16 +19,18 @@
for a in data.actuator_states:
print " actuator: %s" % a.name
print " encoder_count: %d" % a.encoder_count
+ print " position: %d" % a.position
print " timestamp: %.4f" % a.timestamp
print " encoder_velocity: %.4f" % a.encoder_velocity
+ print " velocity: %.4f" % a.velocity
print " calibration_reading: %d" % a.calibration_reading
print " last_calibration_high_transition: %d" % a.last_calibration_high_transition
print " last_calibration_low_transition: %d" % a.last_calibration_low_transition
print " is_enabled: %d" % a.is_enabled
print " run_stop_hit: %d" % a.run_stop_hit
- print " last_requested_current: %.4f" % a.last_requested_current
- print " last_commanded_current: %.4f" % a.last_commanded_current
- print " last_measured_current: %.4f" % a.last_measured_current
+ print " last_requested_effort: %.4f" % a.last_requested_effort
+ print " last_commanded_effort: %.4f" % a.last_commanded_effort
+ print " last_measured_effort: %.4f" % a.last_measured_effort
print " motor_voltage: %.4f" % a.motor_voltage
print " num_encoder_errors: %d" % a.num_encoder_errors
Modified: pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp 2008-09-04 23:06:35 UTC (rev 3960)
@@ -248,16 +248,18 @@
ActuatorState *in = &mc_->hw_->actuators_[i]->state_;
out->name = mc_->hw_->actuators_[i]->name_;
out->encoder_count = in->encoder_count_;
+ out->position = in->position_;
out->timestamp = in->timestamp_;
out->encoder_velocity = in->encoder_velocity_;
+ out->velocity = in->velocity_;
out->calibration_reading = in->calibration_reading_;
out->last_calibration_high_transition = in->last_calibration_high_transition_;
out->last_calibration_low_transition = in->last_calibration_low_transition_;
out->is_enabled = in->is_enabled_;
out->run_stop_hit = in->run_stop_hit_;
- out->last_requested_current = in->last_requested_current_;
- out->last_commanded_current = in->last_commanded_current_;
- out->last_measured_current = in->last_measured_current_;
+ out->last_requested_effort = in->last_requested_effort_;
+ out->last_commanded_effort = in->last_commanded_effort_;
+ out->last_measured_effort = in->last_measured_effort_;
out->motor_voltage = in->motor_voltage_;
out->num_encoder_errors = in->num_encoder_errors_;
}
Modified: pkg/trunk/mechanism/mechanism_model/include/mechanism_model/simple_transmission.h
===================================================================
--- pkg/trunk/mechanism/mechanism_model/include/mechanism_model/simple_transmission.h 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/mechanism_model/include/mechanism_model/simple_transmission.h 2008-09-04 23:06:35 UTC (rev 3960)
@@ -53,8 +53,6 @@
bool initXml(TiXmlElement *config, Robot *robot);
double mechanical_reduction_;
- double motor_torque_constant_;
- double pulses_per_revolution_;
void propagatePosition(std::vector<Actuator*>&, std::vector<JointState*>&);
void propagatePositionBackwards(std::vector<JointState*>&, std::vector<Actuator*>&);
Modified: pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/mechanism_model/src/gripper_transmission.cpp 2008-09-04 23:06:35 UTC (rev 3960)
@@ -92,10 +92,9 @@
assert(js.size() == reductions_.size());
for (unsigned int i = 0; i < js.size(); ++i)
{
- double mr = reductions_[i];
- js[i]->position_ = as[0]->state_.encoder_count_ * 2 * M_PI / (mr * pulses_per_revolution_);
- js[i]->velocity_ = as[0]->state_.encoder_velocity_ * 2 * M_PI / (mr * pulses_per_revolution_);
- js[i]->applied_effort_ = as[0]->state_.last_measured_current_ * mr * motor_torque_constant_;
+ js[i]->position_ = as[0]->state_.position_ / reductions_[i];
+ js[i]->velocity_ = as[0]->state_.velocity_ / reductions_[i];
+ js[i]->applied_effort_ = as[0]->state_.last_measured_effort_ * reductions_[i];
}
}
@@ -105,19 +104,18 @@
assert(as.size() == 1);
assert(js.size() == reductions_.size());
- double mean_encoder = 0.0;
- double mean_encoder_v = 0.0;
- double mean_current = 0.0;
+ double mean_position = 0.0;
+ double mean_velocity = 0.0;
+ double mean_effort = 0.0;
for (unsigned int i = 0; i < js.size(); ++i)
{
- double mr = reductions_[i];
- mean_encoder += js[i]->position_ * mr * pulses_per_revolution_ / (2 * M_PI);
- mean_encoder_v += js[i]->velocity_ * mr * pulses_per_revolution_ / (2 * M_PI);
- mean_current += js[i]->applied_effort_ / (mr * motor_torque_constant_);
+ mean_position += js[i]->position_ * reductions_[i];
+ mean_velocity += js[i]->velocity_ * reductions_[i];
+ mean_effort += js[i]->applied_effort_ / (reductions_[i]);
}
- as[0]->state_.encoder_count_ = mean_encoder / js.size();
- as[0]->state_.encoder_velocity_ = mean_encoder_v / js.size();
- as[0]->state_.last_measured_current_ = mean_current / js.size();
+ as[0]->state_.position_ = mean_position / js.size();
+ as[0]->state_.velocity_ = mean_velocity / js.size();
+ as[0]->state_.last_measured_effort_ = mean_effort / js.size();
}
void GripperTransmission::propagateEffort(
@@ -130,9 +128,9 @@
for (unsigned int i = 0; i < js.size(); ++i)
{
if (fabs(js[i]->commanded_effort_ / (reductions_[i])) > fabs(strongest))
- strongest = js[i]->commanded_effort_ / (reductions_[i] * motor_torque_constant_);
+ strongest = js[i]->commanded_effort_ / reductions_[i];
}
- as[0]->command_.current_ = strongest;
+ as[0]->command_.effort_ = strongest;
}
void GripperTransmission::propagateEffortBackwards(
@@ -154,8 +152,7 @@
double pid_effort = pids_[i].updatePid(err, 0.001);
js[i]->commanded_effort_ =
- pid_effort / reductions_[i] +
- as[0]->command_.current_ * reductions_[i] * motor_torque_constant_;
+ pid_effort / reductions_[i] + as[0]->command_.effort_ * reductions_[i];
}
}
Modified: pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp
===================================================================
--- pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/mechanism/mechanism_model/src/simple_transmission.cpp 2008-09-04 23:06:35 UTC (rev 3960)
@@ -62,9 +62,7 @@
}
actuator_names_.push_back(actuator_name);
- mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText()),
- motor_torque_constant_ = atof(elt->FirstChildElement("motorTorqueConstant")->GetText()),
- pulses_per_revolution_ = atof(elt->FirstChildElement("pulsesPerRevolution")->GetText());
+ mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
return true;
}
@@ -73,9 +71,9 @@
{
assert(as.size() == 1);
assert(js.size() == 1);
- js[0]->position_ = ((double)as[0]->state_.encoder_count_*2*M_PI)/(pulses_per_revolution_ * mechanical_reduction_);
- js[0]->velocity_ = ((double)as[0]->state_.encoder_velocity_*2*M_PI)/(pulses_per_revolution_ * mechanical_reduction_);
- js[0]->applied_effort_ = as[0]->state_.last_measured_current_ * (motor_torque_constant_ * mechanical_reduction_);
+ js[0]->position_ = as[0]->state_.position_ / mechanical_reduction_;
+ js[0]->velocity_ = as[0]->state_.velocity_ / mechanical_reduction_;
+ js[0]->applied_effort_ = as[0]->state_.last_measured_effort_ * mechanical_reduction_;
}
void SimpleTransmission::propagatePositionBackwards(
@@ -83,9 +81,9 @@
{
assert(as.size() == 1);
assert(js.size() == 1);
- as[0]->state_.encoder_count_ = (int)(js[0]->position_ * pulses_per_revolution_ * mechanical_reduction_ / (2*M_PI));
- as[0]->state_.encoder_velocity_ = js[0]->velocity_ * pulses_per_revolution_ * mechanical_reduction_ / (2*M_PI);
- as[0]->state_.last_measured_current_ = js[0]->applied_effort_ / (motor_torque_constant_ * mechanical_reduction_);
+ as[0]->state_.position_ = js[0]->position_ * mechanical_reduction_;
+ as[0]->state_.velocity_ = js[0]->velocity_ * mechanical_reduction_;
+ as[0]->state_.last_measured_effort_ = js[0]->applied_effort_ / mechanical_reduction_;
}
void SimpleTransmission::propagateEffort(
@@ -93,7 +91,7 @@
{
assert(as.size() == 1);
assert(js.size() == 1);
- as[0]->command_.current_ = js[0]->commanded_effort_/(motor_torque_constant_ * mechanical_reduction_);
+ as[0]->command_.effort_ = js[0]->commanded_effort_ / mechanical_reduction_;
as[0]->command_.enable_ = true;
}
@@ -102,5 +100,5 @@
{
assert(as.size() == 1);
assert(js.size() == 1);
- js[0]->commanded_effort_ = as[0]->command_.current_ * motor_torque_constant_ * mechanical_reduction_;
+ js[0]->commanded_effort_ = as[0]->command_.effort_ * mechanical_reduction_;
}
Modified: pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp
===================================================================
--- pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp 2008-09-04 22:32:36 UTC (rev 3959)
+++ pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp 2008-09-04 23:06:35 UTC (rev 3960)
@@ -111,7 +111,7 @@
for (unsigned int i = 0; i < ec.hw_->actuators_.size(); ++i)
{
ec.hw_->actuators_[i]->command_.enable_ = false;
- ec.hw_->actuators_[i]->command_.current_ = 0;
+ ec.hw_->actuators_[i]->command_.effort_ = 0;
}
ec.update();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <rob...@us...> - 2008-09-04 23:29:59
|
Revision: 3962
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3962&view=rev
Author: rob_wheeler
Date: 2008-09-04 23:30:10 +0000 (Thu, 04 Sep 2008)
Log Message:
-----------
Add zero offset for actuators
Modified Paths:
--------------
pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp
pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp 2008-09-04 23:22:38 UTC (rev 3961)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg05.cpp 2008-09-04 23:30:10 UTC (rev 3962)
@@ -194,7 +194,7 @@
state.timestamp_ = current_status.timestamp_ / 1e+6;
state.encoder_count_ = current_status.encoder_count_;
- state.position_ = double(current_status.encoder_count_) / pulses_per_revolution * 2 * M_PI;
+ state.position_ = double(current_status.encoder_count_ - state.zero_offset_) / pulses_per_revolution * 2 * M_PI;
state.encoder_velocity_ = double(int(current_status.encoder_count_ - last_status.encoder_count_))
/ (current_status.timestamp_ - last_status.timestamp_) * 1e+6;
state.velocity_ = state.encoder_velocity_ / pulses_per_revolution * 2 * M_PI;
Modified: pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h
===================================================================
--- pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-09-04 23:22:38 UTC (rev 3961)
+++ pkg/trunk/mechanism/hardware_interface/include/hardware_interface/hardware_interface.h 2008-09-04 23:30:10 UTC (rev 3962)
@@ -49,7 +49,8 @@
last_requested_effort_(0),
last_commanded_effort_(0),
last_measured_effort_(0),
- num_encoder_errors_(0)
+ num_encoder_errors_(0),
+ zero_offset_(0)
{}
double timestamp_;
@@ -73,6 +74,8 @@
int num_encoder_errors_;
int num_communication_errors_;
+
+ int zero_offset_; // In encoder counts
};
class ActuatorCommand
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ei...@us...> - 2008-09-05 00:02:56
|
Revision: 3967
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3967&view=rev
Author: eitanme
Date: 2008-09-05 00:03:02 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
Initital commit for PR2 local controller
Added Paths:
-----------
pkg/trunk/trajectory_rollout/
pkg/trunk/trajectory_rollout/CMakeLists.txt
pkg/trunk/trajectory_rollout/Makefile
pkg/trunk/trajectory_rollout/include/
pkg/trunk/trajectory_rollout/include/map_cell.h
pkg/trunk/trajectory_rollout/include/map_grid.h
pkg/trunk/trajectory_rollout/include/trajectory.h
pkg/trunk/trajectory_rollout/include/trajectory_controller.h
pkg/trunk/trajectory_rollout/include/trajectory_inc.h
pkg/trunk/trajectory_rollout/lib/
pkg/trunk/trajectory_rollout/manifest.xml
pkg/trunk/trajectory_rollout/msg/
pkg/trunk/trajectory_rollout/src/
pkg/trunk/trajectory_rollout/src/map_cell.cpp
pkg/trunk/trajectory_rollout/src/map_grid.cpp
pkg/trunk/trajectory_rollout/src/tests.cpp
pkg/trunk/trajectory_rollout/src/trajectory.cpp
pkg/trunk/trajectory_rollout/src/trajectory_controller.cpp
Added: pkg/trunk/trajectory_rollout/CMakeLists.txt
===================================================================
--- pkg/trunk/trajectory_rollout/CMakeLists.txt (rev 0)
+++ pkg/trunk/trajectory_rollout/CMakeLists.txt 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,6 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(trajectory_rollout)
+
+rospack_add_library(trajectory_rollout src/map_cell.cpp src/map_grid.cpp src/trajectory_controller.cpp src/trajectory.cpp)
+rospack_add_executable(tests src/tests.cpp src/map_cell.cpp src/map_grid.cpp src/trajectory_controller.cpp src/trajectory.cpp)
Added: pkg/trunk/trajectory_rollout/Makefile
===================================================================
--- pkg/trunk/trajectory_rollout/Makefile (rev 0)
+++ pkg/trunk/trajectory_rollout/Makefile 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Added: pkg/trunk/trajectory_rollout/include/map_cell.h
===================================================================
--- pkg/trunk/trajectory_rollout/include/map_cell.h (rev 0)
+++ pkg/trunk/trajectory_rollout/include/map_cell.h 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,63 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#ifndef MAP_CELL_H_
+#define MAP_CELL_H_
+
+#include "trajectory_inc.h"
+
+//Information contained in each map cell
+class MapCell{
+ public:
+ //default constructor
+ MapCell();
+
+ MapCell(const MapCell& mc);
+ MapCell(const MapCell* mc);
+
+ //cell index in the grid map
+ unsigned ci, cj;
+
+ //distance to planner's path
+ double path_dist;
+
+ //distance to goal
+ double goal_dist;
+
+ //occupancy state (-1 = free, 0 = unknown, 1 = occupied)
+ int occ_state;
+
+ //compares two cells based on path_dist so we can use stl priority queues
+ const bool operator< (const MapCell& mc) const;
+};
+#endif
Added: pkg/trunk/trajectory_rollout/include/map_grid.h
===================================================================
--- pkg/trunk/trajectory_rollout/include/map_grid.h (rev 0)
+++ pkg/trunk/trajectory_rollout/include/map_grid.h 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,68 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#ifndef MAP_GRID_H_
+#define MAP_GRID_H_
+
+#include <vector>
+#include <iostream>
+#include "assert.h"
+#include "trajectory_inc.h"
+
+#include "map_cell.h"
+
+//A grid of MapCells
+class MapGrid{
+ public:
+ MapGrid(unsigned rows, unsigned cols);
+
+ //cells will be accessed by (row, col)
+ MapCell& operator() (unsigned row, unsigned col);
+ MapCell operator() (unsigned row, unsigned col) const;
+
+ ~MapGrid(){}
+
+ MapGrid(const MapGrid& mg);
+ MapGrid& operator= (const MapGrid& mg);
+
+ unsigned rows_, cols_;
+ std::vector<MapCell> map_;
+
+ //lower left corner of grid in world space
+ double origin_x, origin_y;
+
+ //grid scale in meters/cell
+ double scale;
+};
+
+#endif
Added: pkg/trunk/trajectory_rollout/include/trajectory.h
===================================================================
--- pkg/trunk/trajectory_rollout/include/trajectory.h (rev 0)
+++ pkg/trunk/trajectory_rollout/include/trajectory.h 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,73 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#ifndef TRAJECTORY_H_
+#define TRAJECTORY_H_
+
+#include <vector>
+
+//stores the information for a point on a trajectory
+class TrajectoryPoint{
+ public:
+ TrajectoryPoint(double t, double x, double y, double theta,
+ double xv, double yv, double thetav)
+ : t_(t), x_(x), y_(y), theta_(theta), xv_(xv), yv_(yv), thetav_(thetav)
+ {}
+
+ TrajectoryPoint()
+ : t_(0), x_(0), y_(0), theta_(0), xv_(0), yv_(0), thetav_(0)
+ {}
+
+ //time
+ double t_;
+
+ //position at time t
+ double x_, y_, theta_;
+
+ //velocity at time t
+ double xv_, yv_, thetav_;
+};
+
+//holds a trajectory generated by an x, y, and theta velocity
+class Trajectory {
+ public:
+ Trajectory(double xv, double yv, double thetav, double steps);
+
+ void addPoint(int step, TrajectoryPoint tp);
+
+ double xv_, yv_, thetav_;
+
+ //storage for points in the trajectory
+ std::vector<TrajectoryPoint> points_;
+};
+#endif
Added: pkg/trunk/trajectory_rollout/include/trajectory_controller.h
===================================================================
--- pkg/trunk/trajectory_rollout/include/trajectory_controller.h (rev 0)
+++ pkg/trunk/trajectory_rollout/include/trajectory_controller.h 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,90 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#ifndef TRAJECTORY_CONTROLLER_H_
+#define TRAJECTORY_CONTROLLER_H_
+
+#include <vector>
+#include <iostream>
+#include <math.h>
+#include <utility>
+
+#include "map_cell.h"
+#include "map_grid.h"
+#include "trajectory.h"
+
+#define SIM_STEPS 20
+#define SIM_TIME 2 //in seconds
+
+#define MAX(x, y) x > y ? x : y
+#define MIN(x, y) x < y ? x : y
+#define VALID_CELL(map, i, j) ((i >= 0) && (i < (int)map.rows_) && (j >= 0) && (j < (int)map.cols_))
+
+//Based on the plan from the path planner, determine what velocities to send to the robot
+class TrajectoryController {
+ public:
+ //create a controller given a map, path, and acceleration limits of the robot
+ TrajectoryController(MapGrid mg, std::vector<std::pair<int, int> > path, double acc_x, double acc_y, double acc_theta);
+
+ //compute the distance from each cell in the map grid to the planned path
+ void computePathDistance();
+
+ //compute the distance from an individual cell to the planned path
+ void cellPathDistance(MapCell* current, int di, int dj);
+
+ //update neighboring path distance
+ void updateNeighbors(MapCell* current);
+
+ //create a trajectory given the current pose of the robot and selected velocities
+ void generateTrajectory(double x, double y, double theta, double vx, double vy,
+ double vtheta, double num_steps, double sim_time);
+
+ //compute position based on velocity
+ double computeNewPosition(double xi, double v, double dt);
+
+ //compute velocity based on acceleration
+ double computeNewVelocity(double vg, double vi, double amax, double dt);
+
+ //the map passed on from the planner
+ MapGrid map_;
+
+ //the path computed by the planner
+ std::vector<std::pair<int, int> > planned_path_;
+
+ //the acceleration limits of the robot
+ double acc_x_, acc_y_, acc_theta_;
+
+};
+
+
+#endif
Added: pkg/trunk/trajectory_rollout/include/trajectory_inc.h
===================================================================
--- pkg/trunk/trajectory_rollout/include/trajectory_inc.h (rev 0)
+++ pkg/trunk/trajectory_rollout/include/trajectory_inc.h 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,47 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#ifndef TRAJECTORY_INC_H_
+#define TRAJECTORY_INC_H_
+
+#include <limits>
+
+#ifndef DBL_MAX /* Max decimal value of a double */
+#define DBL_MAX std::numeric_limits<double>::max() // 1.7976931348623157e+308
+#endif
+
+#ifndef DBL_MIN //Min decimal value of a double
+#define DBL_MIN std::numeric_limits<double>::min() // 2.2250738585072014e-308
+#endif
+
+#endif
Added: pkg/trunk/trajectory_rollout/manifest.xml
===================================================================
--- pkg/trunk/trajectory_rollout/manifest.xml (rev 0)
+++ pkg/trunk/trajectory_rollout/manifest.xml 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,17 @@
+<package>
+ <description>
+ A controller that drives a mobile base in the plane. Given a path from the path
+ planner, the controller determines the dx, dy, dtheta velocities to send to the
+ robot.
+ </description>
+ <author>Eitan Marder-Eppstein</author>
+ <license>BSD</license>
+ <depend package="stl_utils" />
+ <depend package="std_msgs" />
+ <depend package="xmlparam" />
+ <url>http://pr.willowgarage.com</url>
+ <repository>http://pr.willowgarage.com/repos</repository>
+ <export>
+ <cpp cflags='-I${prefix}/include' />
+ </export>
+</package>
Added: pkg/trunk/trajectory_rollout/src/map_cell.cpp
===================================================================
--- pkg/trunk/trajectory_rollout/src/map_cell.cpp (rev 0)
+++ pkg/trunk/trajectory_rollout/src/map_cell.cpp 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,53 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+
+#include "map_cell.h"
+
+MapCell::MapCell()
+ : ci(0), cj(0), path_dist(DBL_MAX), goal_dist(DBL_MAX), occ_state(0)
+{}
+
+MapCell::MapCell(const MapCell& mc)
+ : ci(mc.ci), cj(mc.cj), path_dist(mc.path_dist), goal_dist(mc.goal_dist),
+ occ_state(mc.occ_state)
+{}
+
+MapCell::MapCell(const MapCell* mc)
+ : ci(mc->ci), cj(mc->cj), path_dist(mc->path_dist), goal_dist(mc->goal_dist),
+ occ_state(mc->occ_state)
+{}
+
+const bool MapCell::operator< (const MapCell& mc) const{
+ return path_dist < mc.path_dist;
+}
Added: pkg/trunk/trajectory_rollout/src/map_grid.cpp
===================================================================
--- pkg/trunk/trajectory_rollout/src/map_grid.cpp (rev 0)
+++ pkg/trunk/trajectory_rollout/src/map_grid.cpp 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,79 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#include "map_grid.h"
+
+using namespace std;
+
+MapGrid::MapGrid(unsigned rows, unsigned cols)
+ : rows_(rows), cols_(cols)
+{
+ //don't allow construction of zero size grid
+ assert(rows != 0 && cols != 0);
+
+ map_.resize(rows * cols);
+
+ //make each cell aware of its location in the grid
+ for(unsigned int i = 0; i < rows; ++i){
+ for(unsigned int j = 0; j < cols; ++ j){
+ map_[cols * i + j].ci = i;
+ map_[cols * i + j].cj = j;
+ }
+ }
+}
+
+MapCell& MapGrid::operator() (unsigned row, unsigned col){
+ assert(row < rows_ && col < cols_);
+ //check for legal index
+ return map_[cols_ * row + col];
+}
+
+MapCell MapGrid::operator() (unsigned row, unsigned col) const {
+ //check for legal index
+ assert(row < rows_ && col < cols_);
+ return map_[cols_ * row + col];
+}
+
+
+MapGrid::MapGrid(const MapGrid& mg){
+ rows_ = mg.rows_;
+ cols_ = mg.cols_;
+ map_ = mg.map_;
+}
+
+MapGrid& MapGrid::operator= (const MapGrid& mg){
+ rows_ = mg.rows_;
+ cols_ = mg.cols_;
+ map_ = mg.map_;
+ return *this;
+}
Added: pkg/trunk/trajectory_rollout/src/tests.cpp
===================================================================
--- pkg/trunk/trajectory_rollout/src/tests.cpp (rev 0)
+++ pkg/trunk/trajectory_rollout/src/tests.cpp 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,119 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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.
+ *********************************************************************/
+#include <iostream>
+#include <vector>
+#include <utility>
+#include "map_cell.h"
+#include "map_grid.h"
+#include "trajectory_controller.h"
+
+using namespace std;
+
+//make sure that we are getting the path distance map expected
+bool testPathDistance(){
+ bool pass = true;
+ vector<pair<int, int> > path;
+
+ MapGrid mg(6, 6);
+
+ //create a path through the world
+ mg(2, 0).path_dist = 0.0;
+ mg(2, 1).path_dist = 0.0;
+ mg(3, 1).path_dist = 0.0;
+ mg(4, 1).path_dist = 0.0;
+ mg(4, 2).path_dist = 0.0;
+ mg(4, 3).path_dist = 0.0;
+ mg(3, 3).path_dist = 0.0;
+ mg(2, 3).path_dist = 0.0;
+ mg(1, 3).path_dist = 0.0;
+ mg(1, 4).path_dist = 0.0;
+ mg(1, 5).path_dist = 0.0;
+ mg(2, 5).path_dist = 0.0;
+ mg(3, 5).path_dist = 0.0;
+
+ //place some obstacles
+ mg(3,2).occ_state = 1;
+ mg(5,3).occ_state = 1;
+ mg(2,4).occ_state = 1;
+ mg(0,5).occ_state = 1;
+
+ //create a trajectory_controller
+ TrajectoryController tc(mg, path, 1, 1, 1);
+
+ tc.computePathDistance();
+
+ //print the results
+ cout.precision(2);
+ for(int k = tc.map_.rows_ - 1 ; k >= 0; --k){
+ for(unsigned int m = 0; m < tc.map_.cols_; ++m){
+ cout << tc.map_(k, m).path_dist << " | ";
+ }
+ cout << endl;
+ }
+ return pass;
+}
+
+//sanity check to make sure the grid functions correctly
+bool testGrid(){
+ bool pass = true;
+ MapGrid mg(10, 10);
+ MapCell mc;
+
+ for(int i = 0; i < 10; ++i){
+ for(int j = 0; j < 10; ++j){
+ mc.ci = i;
+ mc.cj = j;
+ mg(i, j) = mc;
+ }
+ }
+
+ for(int i = 0; i < 10; ++i){
+ for(int j = 0; j < 10; ++j){
+ if(!mg(i, j).ci == i || !mg(i, j).cj == j)
+ pass = false;
+ }
+ }
+ return pass;
+}
+
+//test some stuff
+int main(int argc, char** argv){
+ cout << "Test Grid: ";
+ testGrid() ? cout << "PASS" : cout << "FAIL";
+ cout << endl;
+
+ cout << "Test Path Distance: " << endl;
+ testPathDistance() ? cout << "PASS" : cout << "FAIL";
+ cout << endl;
+}
Added: pkg/trunk/trajectory_rollout/src/trajectory.cpp
===================================================================
--- pkg/trunk/trajectory_rollout/src/trajectory.cpp (rev 0)
+++ pkg/trunk/trajectory_rollout/src/trajectory.cpp 2008-09-05 00:03:02 UTC (rev 3967)
@@ -0,0 +1,46 @@
+/*********************************************************************
+ * Software License Agreement (BSD License)
+ *
+ * Copyright (c) 2008, Willow Garage, Inc.
+ * All rights reserved.
+ *
+ * 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.
+ * * Neither the name of the Willow Garage nor the names of its
+ * contributors may 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 S...
[truncated message content] |
|
From: <tf...@us...> - 2008-09-05 00:09:31
|
Revision: 3968
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3968&view=rev
Author: tfoote
Date: 2008-09-05 00:09:37 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
moving Position, Euler, Vector, and Quaternion structs out of Pose3D class to allow swigging of Pose3D
Modified Paths:
--------------
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
pkg/trunk/motion_planning/kinematic_planning/include/RKPConstraintEvaluator.h
pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp
pkg/trunk/util/libTF/include/libTF/Pose3D.h
pkg/trunk/util/libTF/src/Pose3D.cpp
pkg/trunk/util/libTF/src/libTF.cpp
pkg/trunk/util/libTF/src/test/main.cpp
pkg/trunk/util/libTF/src/test/testMatrix.cc
pkg/trunk/util/libTF/src/test/testMatrixQuaternion.cc
pkg/trunk/util/libTF/test/pose3d_unittest.cpp
pkg/trunk/util/rosTF/src/rosTF.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/helpers/robot.cpp
Modified: pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h 2008-09-05 00:09:37 UTC (rev 3968)
@@ -75,7 +75,7 @@
~BaseParam(){}
- libTF::Pose3D::Vector pos_; /** position of the link*/
+ libTF::Vector pos_; /** position of the link*/
std::string name_; /** name of joint corresponding to the link */
@@ -120,13 +120,13 @@
*
* \param double pos Position command to issue
*/
- void setCommand(libTF::Pose3D::Vector cmd_vel);
+ void setCommand(libTF::Vector cmd_vel);
/*!
* \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
*/
- libTF::Pose3D::Vector getCommand();
+ libTF::Vector getCommand();
/*!
@@ -212,7 +212,7 @@
* \param vel - Vector, vel.x and vel.y represent translational velocities in X and Y directions, vel.z represents rotational(angular velocity)
* \return point 2D velocity with .z component set to zero.
*/
- libTF::Pose3D::Vector computePointVelocity2D(const libTF::Pose3D::Vector& pos, const libTF::Pose3D::Vector& vel);
+ libTF::Vector computePointVelocity2D(const libTF::Vector& pos, const libTF::Vector& vel);
/*!
* \brief update the individual joint controllers
@@ -223,25 +223,25 @@
/*!
* \brief speed command vector used internally
*/
- libTF::Pose3D::Vector cmd_vel_;
+ libTF::Vector cmd_vel_;
/*!
* \brief Input speed command vector.
*/
- libTF::Pose3D::Vector cmd_vel_t_;
+ libTF::Vector cmd_vel_t_;
/*!
* \brief Position of the robot computed by odometry.
*/
- libTF::Pose3D::Vector base_odom_position_;
+ libTF::Vector base_odom_position_;
/*!
* \brief Speed of the robot computed by odometry.
*/
- libTF::Pose3D::Vector base_odom_velocity_;
+ libTF::Vector base_odom_velocity_;
/*!
@@ -286,7 +286,7 @@
void computeWheelPositions();
- std::vector<libTF::Pose3D::Vector> base_wheels_position_; /** vector of current wheel positions */
+ std::vector<libTF::Vector> base_wheels_position_; /** vector of current wheel positions */
/*!
Modified: pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -67,7 +67,7 @@
}
// Set the joint position command
-void BaseController::setCommand(libTF::Pose3D::Vector cmd_vel)
+void BaseController::setCommand(libTF::Vector cmd_vel)
{
pthread_mutex_lock(&base_controller_lock_);
//std::cout << "command received : " << cmd_vel_t_ << std::endl;
@@ -77,9 +77,9 @@
pthread_mutex_unlock(&base_controller_lock_);
}
-libTF::Pose3D::Vector BaseController::getCommand()// Return the current position command
+libTF::Vector BaseController::getCommand()// Return the current position command
{
- libTF::Pose3D::Vector cmd_vel;
+ libTF::Vector cmd_vel;
pthread_mutex_lock(&base_controller_lock_);
cmd_vel.x = cmd_vel_t_.x;
cmd_vel.y = cmd_vel_t_.y;
@@ -139,7 +139,7 @@
base_wheels_.push_back(base_object);
wheel_speed_actual_.push_back(0);
- libTF::Pose3D::Vector *v=new libTF::Pose3D::Vector();
+ libTF::Vector *v=new libTF::Vector();
base_wheels_position_.push_back(*v);
num_wheels_++;
}
@@ -247,7 +247,7 @@
void BaseController::computeWheelPositions()
{
- libTF::Pose3D::Vector res1;
+ libTF::Vector res1;
double steer_angle;
for(int i=0; i < num_wheels_; i++)
{
@@ -302,7 +302,7 @@
void BaseController::computeAndSetCasterSteer()
{
- libTF::Pose3D::Vector result;
+ libTF::Vector result;
double steer_angle_desired;
double error_steer;
for(int i=0; i < num_casters_; i++)
@@ -320,10 +320,10 @@
void BaseController::computeAndSetWheelSpeeds()
{
- libTF::Pose3D::Vector wheel_point_velocity;
- libTF::Pose3D::Vector wheel_point_velocity_projected;
- libTF::Pose3D::Vector wheel_caster_steer_component;
- libTF::Pose3D::Vector caster_2d_velocity;
+ libTF::Vector wheel_point_velocity;
+ libTF::Vector wheel_point_velocity_projected;
+ libTF::Vector wheel_caster_steer_component;
+ libTF::Vector caster_2d_velocity;
caster_2d_velocity.x = 0;
caster_2d_velocity.y = 0;
@@ -379,7 +379,7 @@
pr2_controllers::SetBaseCommand::request &req,
pr2_controllers::SetBaseCommand::response &resp)
{
- libTF::Pose3D::Vector command;
+ libTF::Vector command;
command.x = req.x_vel;
command.y = req.y_vel;
command.z = req.theta_vel;
@@ -394,7 +394,7 @@
void BaseControllerNode::setCommand(double vx, double vy, double vw)
{
- libTF::Pose3D::Vector command;
+ libTF::Vector command;
command.x = vx;
command.y = vy;
command.z = vw;
@@ -407,7 +407,7 @@
pr2_controllers::GetBaseCommand::request &req,
pr2_controllers::GetBaseCommand::response &resp)
{
- libTF::Pose3D::Vector command;
+ libTF::Vector command;
command = c_->getCommand();
resp.x_vel = command.x;
resp.y_vel = command.y;
@@ -449,9 +449,9 @@
}
-Pose3D::Vector BaseController::computePointVelocity2D(const Pose3D::Vector& pos, const Pose3D::Vector& vel)
+Vector BaseController::computePointVelocity2D(const Vector& pos, const Vector& vel)
{
- Pose3D::Vector result;
+ Vector result;
result.x = vel.x - pos.y * vel.z;
result.y = vel.y + pos.x * vel.z;
@@ -463,11 +463,11 @@
void BaseController::computeOdometry(double time)
{
double dt = time-last_time_;
-// libTF::Pose3D::Vector base_odom_delta = rotate2D(base_odom_velocity_*dt,base_odom_position_.z);
+// libTF::Vector base_odom_delta = rotate2D(base_odom_velocity_*dt,base_odom_position_.z);
computeBaseVelocity();
- libTF::Pose3D::Vector base_odom_delta = (base_odom_velocity_*dt).rot2D(base_odom_position_.z);
+ libTF::Vector base_odom_delta = (base_odom_velocity_*dt).rot2D(base_odom_position_.z);
// if(isnan(dt))
// {
@@ -604,8 +604,8 @@
// wheel_radius_ = wheel_geom->radius;
// BaseCasterGeomParam caster;
-// libTF::Pose3D::Vector wheel_l;
-// libTF::Pose3D::Vector wheel_r;
+// libTF::Vector wheel_l;
+// libTF::Vector wheel_r;
// wheel_l.x = 0;
// wheel_l.y = wheel_base_/2.0;
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-09-05 00:09:37 UTC (rev 3968)
@@ -78,11 +78,11 @@
bool containsPoint(double x, double y, double z) const
{
- libTF::Pose3D::Position pt(x, y, z);
+ libTF::Position pt(x, y, z);
return containsPoint(pt);
}
- virtual bool containsPoint(const libTF::Pose3D::Position &p) const = 0;
+ virtual bool containsPoint(const libTF::Position &p) const = 0;
protected:
@@ -106,7 +106,7 @@
{
}
- virtual bool containsPoint(const libTF::Pose3D::Position &p) const
+ virtual bool containsPoint(const libTF::Position &p) const
{
double dx = m_center.x - p.x;
double dy = m_center.y - p.y;
@@ -128,7 +128,7 @@
m_pose.getPosition(m_center);
}
- libTF::Pose3D::Position m_center;
+ libTF::Position m_center;
double m_radius;
double m_radius2;
@@ -146,7 +146,7 @@
{
}
- virtual bool containsPoint(const libTF::Pose3D::Position &p) const
+ virtual bool containsPoint(const libTF::Position &p) const
{
double vx = p.x - m_center.x;
double vy = p.y - m_center.y;
@@ -188,10 +188,10 @@
m_pose.applyToVector(m_normalB2);
}
- libTF::Pose3D::Position m_center;
- libTF::Pose3D::Vector m_normalH;
- libTF::Pose3D::Vector m_normalB1;
- libTF::Pose3D::Vector m_normalB2;
+ libTF::Position m_center;
+ libTF::Vector m_normalH;
+ libTF::Vector m_normalB1;
+ libTF::Vector m_normalB2;
double m_length;
double m_length2;
@@ -212,7 +212,7 @@
{
}
- virtual bool containsPoint(const libTF::Pose3D::Position &p) const
+ virtual bool containsPoint(const libTF::Position &p) const
{
double vx = p.x - m_center.x;
double vy = p.y - m_center.y;
@@ -263,10 +263,10 @@
m_pose.applyToVector(m_normalW);
}
- libTF::Pose3D::Position m_center;
- libTF::Pose3D::Vector m_normalL;
- libTF::Pose3D::Vector m_normalW;
- libTF::Pose3D::Vector m_normalH;
+ libTF::Position m_center;
+ libTF::Vector m_normalL;
+ libTF::Vector m_normalW;
+ libTF::Vector m_normalH;
double m_length;
double m_width;
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -131,9 +131,9 @@
libTF::Pose3D &pose = m_kgeoms[model_id].geom[i]->link->globalTrans;
dGeomID geom = m_kgeoms[model_id].geom[i]->geom;
- libTF::Pose3D::Position pos = pose.getPosition();
+ libTF::Position pos = pose.getPosition();
dGeomSetPosition(geom, pos.x, pos.y, pos.z);
- libTF::Pose3D::Quaternion quat = pose.getQuaternion();
+ libTF::Quaternion quat = pose.getQuaternion();
dQuaternion q; q[0] = quat.w; q[1] = quat.x; q[2] = quat.y; q[3] = quat.z;
dGeomSetQuaternion(geom, q);
}
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -79,7 +79,7 @@
for (unsigned int k=0; k<3; k++)
axes[j][k] = mat.element(j,k);
- libTF::Pose3D::Position libTFpos;
+ libTF::Position libTFpos;
links[i]->globalTrans.getPosition(libTFpos);
float pos[3] = {libTFpos.x, libTFpos.y, libTFpos.z};
const double *size = static_cast<planning_models::KinematicModel::Box*>(links[i]->shape)->size;
@@ -99,7 +99,7 @@
for (unsigned int k=0; k<3; k++)
axes[j][k] = mat.element(j,k);
- libTF::Pose3D::Position libTFpos;
+ libTF::Position libTFpos;
links[i]->globalTrans.getPosition(libTFpos);
float pos[3] = {libTFpos.x, libTFpos.y, libTFpos.z };
float radius = static_cast<planning_models::KinematicModel::Cylinder*>(links[i]->shape)->radius;
@@ -113,7 +113,7 @@
case planning_models::KinematicModel::Shape::SPHERE:
{
- libTF::Pose3D::Position libTFpos;
+ libTF::Position libTFpos;
links[i]->globalTrans.getPosition(libTFpos);
float pos[3] = {libTFpos.x, libTFpos.y, libTFpos.z};
float radius = static_cast<planning_models::KinematicModel::Sphere*>(links[i]->shape)->radius;
Modified: pkg/trunk/motion_planning/kinematic_planning/include/RKPConstraintEvaluator.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/RKPConstraintEvaluator.h 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/motion_planning/kinematic_planning/include/RKPConstraintEvaluator.h 2008-09-05 00:09:37 UTC (rev 3968)
@@ -108,7 +108,7 @@
case robot_msgs::PoseConstraint::ONLY_POSITION:
if (distPos)
{
- libTF::Pose3D::Position bodyPos;
+ libTF::Position bodyPos;
m_link->globalTrans.getPosition(bodyPos);
double dx = bodyPos.x - m_pc.pose.position.x;
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/src/urdf2gazebo.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -75,11 +75,11 @@
void addTransform(TiXmlElement *elem, const::libTF::Pose3D& transform)
{
- libTF::Pose3D::Position pz;
+ libTF::Position pz;
transform.getPosition(pz);
double cpos[3] = { pz.x, pz.y, pz.z };
- libTF::Pose3D::Euler eu;
+ libTF::Euler eu;
transform.getEuler(eu);
double crot[3] = { eu.roll, eu.pitch, eu.yaw };
Modified: pkg/trunk/util/libTF/include/libTF/Pose3D.h
===================================================================
--- pkg/trunk/util/libTF/include/libTF/Pose3D.h 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/include/libTF/Pose3D.h 2008-09-05 00:09:37 UTC (rev 3968)
@@ -46,183 +46,184 @@
namespace libTF
{
- /** \brief A class used to store and do basic minipulations of 3D transformations
- *
- */
- class Pose3D
- {
- friend class Pose3DCache;
-
- public:
- /** \brief A struct to represent the translational component (a point) */
- struct Position
- {
- double x,y,z;
- /** \brief Constructor */
- Position():x(0),y(0),z(0){;};
- /** \brief Constructor */
- Position(double x, double y, double z):x(x),y(y),z(z){;};
- /** \brief operator overloading for the + operator */
- Position operator+(const Position &rhs){
- Position result;
- result.x = x + rhs.x;
- result.y = y + rhs.y;
- result.z = z + rhs.z;
- return result;
- }
+/** \brief A struct to represent the translational component (a point) */
+struct Position
+{
+ double x,y,z;
+ /** \brief Constructor */
+ Position():x(0),y(0),z(0){;};
+ /** \brief Constructor */
+ Position(double x, double y, double z):x(x),y(y),z(z){;};
+ /** \brief operator overloading for the + operator */
+ Position operator+(const Position &rhs){
+ Position result;
+ result.x = x + rhs.x;
+ result.y = y + rhs.y;
+ result.z = z + rhs.z;
+ return result;
+ }
- /** \brief operator overloading for the += operator */
- Position & operator+=(const Position &rhs){
- x += rhs.x;
- y += rhs.y;
- z += rhs.z;
- return *this;
- }
+ /** \brief operator overloading for the += operator */
+ Position & operator+=(const Position &rhs){
+ x += rhs.x;
+ y += rhs.y;
+ z += rhs.z;
+ return *this;
+ }
- /** \brief operator overloading for the - operator */
- Position operator-(const Position &rhs){
- Position result;
- result.x = x - rhs.x;
- result.y = y - rhs.y;
- result.z = z - rhs.z;
- return result;
- }
+ /** \brief operator overloading for the - operator */
+ Position operator-(const Position &rhs){
+ Position result;
+ result.x = x - rhs.x;
+ result.y = y - rhs.y;
+ result.z = z - rhs.z;
+ return result;
+ }
- /** \brief operator overloading for the -= operator */
- Position & operator-=(const Position &rhs){
- x -= rhs.x;
- y -= rhs.y;
- z -= rhs.z;
- return *this;
- }
+ /** \brief operator overloading for the -= operator */
+ Position & operator-=(const Position &rhs){
+ x -= rhs.x;
+ y -= rhs.y;
+ z -= rhs.z;
+ return *this;
+ }
- /** \brief operator overloading for the *= operator */
- Position & operator*=(double rhs){
- x *= rhs;
- y *= rhs;
- z *= rhs;
- return *this;
- }
+ /** \brief operator overloading for the *= operator */
+ Position & operator*=(double rhs){
+ x *= rhs;
+ y *= rhs;
+ z *= rhs;
+ return *this;
+ }
- /** \brief operator overloading for the * operator */
- Position operator*(double rhs){
- Position result;
- result.x = x*rhs;
- result.y = y*rhs;
- result.z = z*rhs;
- return result;
- }
+ /** \brief operator overloading for the * operator */
+ Position operator*(double rhs){
+ Position result;
+ result.x = x*rhs;
+ result.y = y*rhs;
+ result.z = z*rhs;
+ return result;
+ }
- /** \brief Rotate a position about the z-axis */
- Position rot2D(double angle){
- Position result;
- double cosa = cos(angle);
- double sina = sin(angle);
- result.x = cosa*x - sina*y;
- result.y = sina*x + cosa*y;
- result.z = z;
- return result;
+ /** \brief Rotate a position about the z-axis */
+ Position rot2D(double angle){
+ Position result;
+ double cosa = cos(angle);
+ double sina = sin(angle);
+ result.x = cosa*x - sina*y;
+ result.y = sina*x + cosa*y;
+ result.z = z;
+ return result;
- }
- };
+ }
+};
- /** \brief A struct to represent vectors */
- struct Vector
- {
- double x,y,z;
+/** \brief A struct to represent vectors */
+struct Vector
+{
+ double x,y,z;
- /** \brief Constructor */
- Vector():x(0),y(0),z(0){;};
- /** \brief Constructor */
- Vector(double x, double y, double z):x(x),y(y),z(z){;};
+ /** \brief Constructor */
+ Vector():x(0),y(0),z(0){;};
+ /** \brief Constructor */
+ Vector(double x, double y, double z):x(x),y(y),z(z){;};
- /** \brief operator overloading for the + operator */
- Vector operator+(const Vector &rhs){
- Vector result;
- result.x = x + rhs.x;
- result.y = y + rhs.y;
- result.z = z + rhs.z;
- return result;
- }
+ /** \brief operator overloading for the + operator */
+ Vector operator+(const Vector &rhs){
+ Vector result;
+ result.x = x + rhs.x;
+ result.y = y + rhs.y;
+ result.z = z + rhs.z;
+ return result;
+ }
- /** \brief operator overloading for the += operator */
- Vector & operator+=(const Vector &rhs){
- x += rhs.x;
- y += rhs.y;
- z += rhs.z;
- return *this;
- }
+ /** \brief operator overloading for the += operator */
+ Vector & operator+=(const Vector &rhs){
+ x += rhs.x;
+ y += rhs.y;
+ z += rhs.z;
+ return *this;
+ }
- /** \brief operator overloading for the - operator */
- Vector operator-(const Vector &rhs){
- Vector result;
- result.x = x - rhs.x;
- result.y = y - rhs.y;
- result.z = z - rhs.z;
- return result;
- }
+ /** \brief operator overloading for the - operator */
+ Vector operator-(const Vector &rhs){
+ Vector result;
+ result.x = x - rhs.x;
+ result.y = y - rhs.y;
+ result.z = z - rhs.z;
+ return result;
+ }
- /** \brief operator overloading for the -= operator */
- Vector & operator-=(const Vector &rhs){
- x -= rhs.x;
- y -= rhs.y;
- z -= rhs.z;
- return *this;
- }
+ /** \brief operator overloading for the -= operator */
+ Vector & operator-=(const Vector &rhs){
+ x -= rhs.x;
+ y -= rhs.y;
+ z -= rhs.z;
+ return *this;
+ }
- /** \brief operator overloading for the *= operator */
- Vector & operator*=(double rhs){
- x *= rhs;
- y *= rhs;
- z *= rhs;
- return *this;
- }
+ /** \brief operator overloading for the *= operator */
+ Vector & operator*=(double rhs){
+ x *= rhs;
+ y *= rhs;
+ z *= rhs;
+ return *this;
+ }
- /** \brief operator overloading for the * operator */
- Vector operator*(double rhs){
- Vector result;
- result.x = x*rhs;
- result.y = y*rhs;
- result.z = z*rhs;
- return result;
- }
+ /** \brief operator overloading for the * operator */
+ Vector operator*(double rhs){
+ Vector result;
+ result.x = x*rhs;
+ result.y = y*rhs;
+ result.z = z*rhs;
+ return result;
+ }
- /** \brief Rotate a vector about the z-axis */
- Vector rot2D(double angle){
- Vector result;
- double cosa = cos(angle);
- double sina = sin(angle);
- result.x = cosa*x - sina*y;
- result.y = sina*x + cosa*y;
- result.z = z;
- return result;
- }
+ /** \brief Rotate a vector about the z-axis */
+ Vector rot2D(double angle){
+ Vector result;
+ double cosa = cos(angle);
+ double sina = sin(angle);
+ result.x = cosa*x - sina*y;
+ result.y = sina*x + cosa*y;
+ result.z = z;
+ return result;
+ }
- };
+};
- /** \brief A struct to represent the quaternion component */
- struct Quaternion
- {
- double x,y,z,w;
+/** \brief A struct to represent the quaternion component */
+struct Quaternion
+{
+ double x,y,z,w;
- /** \brief Constructor */
- Quaternion():x(0),y(0),z(0),w(1){;};
- /** \brief Constructor */
- Quaternion(double x, double y, double z, double w):x(x),y(y),z(z),w(w){;};
+ /** \brief Constructor */
+ Quaternion():x(0),y(0),z(0),w(1){;};
+ /** \brief Constructor */
+ Quaternion(double x, double y, double z, double w):x(x),y(y),z(z),w(w){;};
- };
- /** \brief A struct to represent Euler angles */
- struct Euler
- {
- double yaw, pitch, roll;
- /** \brief Constructor */
- Euler():yaw(0),pitch(0),roll(0){;};
- /** \brief Constructor */
- Euler(double yaw, double pitch, double roll):yaw(yaw),pitch(pitch),roll(roll){;};
+};
+/** \brief A struct to represent Euler angles */
+struct Euler
+{
+ double yaw, pitch, roll;
+ /** \brief Constructor */
+ Euler():yaw(0),pitch(0),roll(0){;};
+ /** \brief Constructor */
+ Euler(double yaw, double pitch, double roll):yaw(yaw),pitch(pitch),roll(roll){;};
- };
+};
+
+/** \brief A class used to store and do basic minipulations of 3D transformations
+ *
+ */
+ class Pose3D
+ {
+ friend class Pose3DCache;
+
+ public:
/* Constructors */
/** \brief Empty Constructor initialize to zero */
@@ -352,7 +353,7 @@
/** \brief A namespace ostream overload for displaying poses */
std::ostream & operator<<(std::ostream& mystream, const Pose3D &pose);
- std::ostream & operator<<(std::ostream& mystream, const Pose3D::Vector &p);
+ std::ostream & operator<<(std::ostream& mystream, const libTF::Vector &p);
}
Modified: pkg/trunk/util/libTF/src/Pose3D.cpp
===================================================================
--- pkg/trunk/util/libTF/src/Pose3D.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/src/Pose3D.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -275,7 +275,7 @@
}
-Pose3D::Euler Pose3D::eulerFromMatrix(const NEWMAT::Matrix & matrix_in, unsigned int solution_number)
+Euler Pose3D::eulerFromMatrix(const NEWMAT::Matrix & matrix_in, unsigned int solution_number)
{
Euler euler_out;
@@ -328,7 +328,7 @@
return euler_out2;
};
-Pose3D::Position Pose3D::positionFromMatrix(const NEWMAT::Matrix & matrix_in)
+Position Pose3D::positionFromMatrix(const NEWMAT::Matrix & matrix_in)
{
Position position;
//get the pointer to the raw data
@@ -410,7 +410,7 @@
axis[2] = zr / d;
}
-Pose3D::Euler Pose3D::getEuler(void) const
+Euler Pose3D::getEuler(void) const
{
return eulerFromMatrix(asMatrix());
}
@@ -420,7 +420,7 @@
eu = eulerFromMatrix(asMatrix());
}
-Pose3D::Quaternion Pose3D::getQuaternion(void) const
+Quaternion Pose3D::getQuaternion(void) const
{
Quaternion quat;
quat.x = xr;
@@ -430,7 +430,7 @@
return quat;
};
-Pose3D::Position Pose3D::getPosition(void) const
+Position Pose3D::getPosition(void) const
{
Position pos;
pos.x = xt;
@@ -599,13 +599,13 @@
//Note not member function
std::ostream & libTF::operator<<(std::ostream& mystream, const Pose3D &storage)
{
- Pose3D::Quaternion q = storage.getQuaternion();
- Pose3D::Position p = storage.getPosition();
+ Quaternion q = storage.getQuaternion();
+ Position p = storage.getPosition();
mystream << "Storage: " << p.x << ", " << p.y << ", " << p.z << ", " << q.x << ", " << q.y << ", " << q.z << ", " << q.w << std::endl;
return mystream;
};
-std::ostream & libTF::operator<<(std::ostream& mystream, const Pose3D::Vector &p)
+std::ostream & libTF::operator<<(std::ostream& mystream, const Vector &p)
{
mystream << p.x << ", " << p.y << ", " << p.z << ", " << std::endl;
return mystream;
Modified: pkg/trunk/util/libTF/src/libTF.cpp
===================================================================
--- pkg/trunk/util/libTF/src/libTF.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/src/libTF.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -223,7 +223,7 @@
NEWMAT::Matrix output = local.i() * Transform;
- Pose3D::Euler eulers = Pose3D::eulerFromMatrix(output,1);
+ Euler eulers = Pose3D::eulerFromMatrix(output,1);
TFEulerYPR retEuler;
retEuler.yaw = eulers.yaw;
Modified: pkg/trunk/util/libTF/src/test/main.cpp
===================================================================
--- pkg/trunk/util/libTF/src/test/main.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/src/test/main.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -21,7 +21,7 @@
NEWMAT::Matrix m = pz.asMatrix();
cout << m;
- Pose3D::Position p;
+ Position p;
p.x = 0;
p.y = 0;
p.z = 1;
Modified: pkg/trunk/util/libTF/src/test/testMatrix.cc
===================================================================
--- pkg/trunk/util/libTF/src/test/testMatrix.cc 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/src/test/testMatrix.cc 2008-09-05 00:09:37 UTC (rev 3968)
@@ -48,7 +48,7 @@
pitch,
roll);
- libTF::Pose3D::Euler out = libTF::Pose3D::eulerFromMatrix(m);
+ libTF::Euler out = libTF::Pose3D::eulerFromMatrix(m);
//TODO add +- 2PI checking/redundant angles checking
// see if input is the same as output (accounting for floating point errors)
Modified: pkg/trunk/util/libTF/src/test/testMatrixQuaternion.cc
===================================================================
--- pkg/trunk/util/libTF/src/test/testMatrixQuaternion.cc 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/src/test/testMatrixQuaternion.cc 2008-09-05 00:09:37 UTC (rev 3968)
@@ -58,8 +58,8 @@
aPose.setFromMatrix(m);
m = aPose.asMatrix();
- libTF::Pose3D::Euler out = libTF::Pose3D::eulerFromMatrix(m);
- libTF::Pose3D::Euler out2 = libTF::Pose3D::eulerFromMatrix(m,2);
+ libTF::Euler out = libTF::Pose3D::eulerFromMatrix(m);
+ libTF::Euler out2 = libTF::Pose3D::eulerFromMatrix(m,2);
// see if input is the same as output (accounting for floating point errors)
if ((fabs(modNPiBy2(out.yaw) - modNPiBy2(yaw)) > 0.001 || fabs(modNPiBy2(out.pitch) - modNPiBy2(pitch)) > 0.001 || fabs(modNPiBy2(out.roll) -modNPiBy2(roll)) > 0.0001) &&
@@ -95,7 +95,7 @@
aPose.setFromMatrix(matrix);
- libTF::Pose3D::Quaternion myquat;
+ libTF::Quaternion myquat;
aPose.getQuaternion(myquat);
std::cout << " MY Quaternion" << myquat.x << " " << myquat.y << " " << myquat.z << " " << myquat.w << std::endl;
Modified: pkg/trunk/util/libTF/test/pose3d_unittest.cpp
===================================================================
--- pkg/trunk/util/libTF/test/pose3d_unittest.cpp 2008-09-05 00:03:02 UTC (rev 3967)
+++ pkg/trunk/util/libTF/test/pose3d_unittest.cpp 2008-09-05 00:09:37 UTC (rev 3968)
@@ -16,22 +16,22 @@
TEST(Pose3D, DefaultConstructor){
Pose3D p;
//EXPECT_EQ(0, p.getMagnitude());
- Pose3D::Euler e = p.getEuler();
+ Euler e = p.getEuler();
EXPECT_EQ(0, e.yaw);
EXPECT_EQ(0, e.pitch);
EXPECT_EQ(0, e.roll);
- Pose3D::Quaternion q = p.getQuaternion();
+ Quaternion q = p.getQuaternion();
EXPECT_EQ(0, q.x);
EXPECT_EQ(0, q.y);
EXPECT_EQ(0, q.z);
EXPECT_EQ(1, q.w);
- Pose3D::Position x = p.getPosition();
+ Position x = p.getPosition();
EXPECT_EQ(0, x.x);
EXPECT_EQ(0, x.y);
...
[truncated message content] |
|
From: <is...@us...> - 2008-09-05 01:39:57
|
Revision: 3971
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3971&view=rev
Author: isucan
Date: 2008-09-05 01:40:07 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
motion planning test for base + right arm
Modified Paths:
--------------
pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml
Modified: pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp
===================================================================
--- pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-09-05 01:11:50 UTC (rev 3970)
+++ pkg/trunk/motion_planning/plan_kinematic_path/src/plan_kinematic_path.cpp 2008-09-05 01:40:07 UTC (rev 3971)
@@ -156,6 +156,39 @@
performCall(req);
}
+
+ void runTestBaseRightArm(void)
+ {
+ robot_srvs::KinematicPlanState::request req;
+
+ req.params.model_id = "pr2::base_right_arm";
+ req.params.distance_metric = "L2Square";
+ req.params.planner_id = "SBL";
+ req.threshold = 0.01;
+ req.interpolate = 1;
+ req.times = 1;
+
+ initialState(req.start_state);
+ req.start_state.vals[0] -= 1.0;
+
+ req.goal_state.set_vals_size(11);
+
+ for (unsigned int i = 0 ; i < 3 ; ++i)
+ req.goal_state.vals[i] = m_basePos[i];
+ req.goal_state.vals[0] += 2.0;
+ req.goal_state.vals[2] = M_PI + M_PI/4.0;
+
+ for (unsigned int i = 3 ; i < req.goal_state.vals_size ; ++i)
+ req.goal_state.vals[i] = 0.0;
+
+ req.allowed_time = 30.0;
+
+ req.params.volumeMin.x = -5.0 + m_basePos[0]; req.params.volumeMin.y = -5.0 + m_basePos[1]; req.params.volumeMin.z = 0.0;
+ req.params.volumeMax.x = 5.0 + m_basePos[0]; req.params.volumeMax.y = 5.0 + m_basePos[1]; req.params.volumeMax.z = 0.0;
+
+ performCall(req);
+ }
+
void performCall(robot_srvs::KinematicPlanState::request &req)
{
robot_srvs::KinematicPlanState::response res;
@@ -189,13 +222,12 @@
req.params.distance_metric = "L2Square";
req.params.planner_id = "RRT";
req.interpolate = 1;
- req.times = 2;
+ req.times = 4;
initialState(req.start_state);
- req.start_state.vals[0] += 0.5;
- req.start_state.vals[1] += 1.5;
- req.start_state.vals[2] = -M_PI/2.0;
+ req.start_state.vals[0] += 2.0;
+ req.start_state.vals[2] = M_PI + M_PI/4.0;
// the goal region is basically the position of a set of bodies
@@ -217,7 +249,7 @@
req.constraints.pose[0].pose.position.z = 0.74;
req.constraints.pose[0].position_distance = 0.01;
*/
- req.allowed_time = 3.0;
+ req.allowed_time = 0.1;
req.params.volumeMin.x = -5.0 + m_basePos[0]; req.params.volumeMin.y = -5.0 + m_basePos[1]; req.params.volumeMin.z = 0.0;
req.params.volumeMax.x = 5.0 + m_basePos[0]; req.params.volumeMax.y = 5.0 + m_basePos[1]; req.params.volumeMax.z = 0.0;
@@ -296,6 +328,9 @@
case 'e':
plan.runTestLeftEEf();
break;
+ case 'x':
+ plan.runTestBaseRightArm();
+ break;
default:
printf("Unknown test\n");
break;
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml 2008-09-05 01:11:50 UTC (rev 3970)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/groups.xml 2008-09-05 01:40:07 UTC (rev 3971)
@@ -95,6 +95,20 @@
forearm_roll_right
wrist_flex_right
gripper_roll_right
+
+ <map name="RRT" flag="planning">
+ <elem key="range" value="0.75" />
+ </map>
+
+ <map name="LazyRRT" flag="planning">
+ <elem key="range" value="0.75" />
+ </map>
+
+ <map name="SBL" flag="planning">
+ <elem key="projection" value="5 6"/>
+ <elem key="celldim" value="0.1 0.1"/>
+ </map>
+
</group>
<group name="arms" flags="planning">
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2008-09-05 17:19:35
|
Revision: 3982
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3982&view=rev
Author: isucan
Date: 2008-09-05 17:19:44 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
more docs on collision spaces, renamed a function
Modified Paths:
--------------
pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h
pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h
pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h
pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environment.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_
@@ -45,7 +45,13 @@
/** @htmlinclude ../../manifest.html
- A class describing an environment for a kinematic robot */
+ A class describing an environment for a kinematic robot. This is
+ the base (abstract) definition. Different implementations are
+ possible. The class is aware of a certain set of fixed
+ (addStatic*) obstacles that never change, a set of obstacles that
+ can change (removed by clearObstacles()) and a set of kinematic
+ robots. The class provides functionality for checking whether a
+ given robot is in collision. */
namespace collision_space
{
@@ -75,7 +81,7 @@
virtual void addPointCloud(unsigned int n, const double* points, double radius = 0.01) = 0;
/** Add a plane to the collision space. Equation it satisfies is a*x+b*y+c*z = d*/
- virtual void addPlane(double a, double b, double c, double d) = 0;
+ virtual void addStaticPlane(double a, double b, double c, double d) = 0;
/** Add a robot model. Ignore robot links if their name is not specified in the string vector */
virtual unsigned int addRobotModel(planning_models::KinematicModel *model, const std::vector<std::string> &links);
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environmentODE.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_ODE_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_ODE_
@@ -84,7 +84,7 @@
virtual void addPointCloud(unsigned int n, const double *points, double radius = 0.01);
/** Add a plane to the collision space. Equation it satisfies is a*x+b*y+c*z = d*/
- virtual void addPlane(double a, double b, double c, double d);
+ virtual void addStaticPlane(double a, double b, double c, double d);
/** Add a robot model. Ignore robot links if their name is not specified in the string vector */
virtual unsigned int addRobotModel(planning_models::KinematicModel *model, const std::vector<std::string> &links);
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/environmentOctree.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan, Matei Ciocarlie */
+/** \author Ioan Sucan, Matei Ciocarlie */
#ifndef COLLISION_SPACE_ENVIRONMENT_MODEL_OCTREE_
#define COLLISION_SPACE_ENVIRONMENT_MODEL_OCTREE_
@@ -76,7 +76,7 @@
virtual void addPointCloud(unsigned int n, const double *points, double radius = 0.01);
/** Add a plane to the collision space. Equation it satisfies is a*x+b*y+c*z = d*/
- virtual void addPlane(double a, double b, double c, double d);
+ virtual void addStaticPlane(double a, double b, double c, double d);
/** Add a robot model. Ignore robot links if their name is not specified in the string vector */
virtual unsigned int addRobotModel(planning_models::KinematicModel *model, const std::vector<std::string> &links);
Modified: pkg/trunk/motion_planning/collision_space/include/collision_space/util.h
===================================================================
--- pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/include/collision_space/util.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#ifndef COLLISION_SPACE_UTIL_
#define COLLISION_SPACE_UTIL_
@@ -40,6 +40,14 @@
#include <libTF/Pose3D.h>
#include <cmath>
+/**
+ This set of classes allows quickly detecting whether a given point
+ is inside an object or not. Only basic (simple) types of objects
+ are supported: spheres, cylinders, boxes. This capability is useful
+ when removing points from inside the robot (when the robot sees its
+ arms, for example).
+*/
+
namespace collision_space
{
@@ -78,7 +86,7 @@
bool containsPoint(double x, double y, double z) const
{
- libTF::Position pt(x, y, z);
+ libTF::Position pt(x, y, z);
return containsPoint(pt);
}
@@ -129,8 +137,8 @@
}
libTF::Position m_center;
- double m_radius;
- double m_radius2;
+ double m_radius;
+ double m_radius2;
};
@@ -178,6 +186,8 @@
m_pose.getPosition(m_center);
+ // this can probably be optimized by simply taking
+ // the columns of the transform matrix
m_normalH.x = m_normalH.y = 0.0; m_normalH.z = 1.0;
m_pose.applyToVector(m_normalH);
@@ -193,10 +203,10 @@
libTF::Vector m_normalB1;
libTF::Vector m_normalB2;
- double m_length;
- double m_length2;
- double m_radius;
- double m_radius2;
+ double m_length;
+ double m_length2;
+ double m_radius;
+ double m_radius2;
};
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environment.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#include <collision_space/environment.h>
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentODE.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
#include <collision_space/environmentODE.h>
#include <algorithm>
@@ -391,7 +391,7 @@
m_collide2.setup();
}
-void collision_space::EnvironmentModelODE::addPlane(double a, double b, double c, double d)
+void collision_space::EnvironmentModelODE::addStaticPlane(double a, double b, double c, double d)
{
dGeomID g = dCreatePlane(m_spaceBasicGeoms, a, b, c, d);
m_basicGeoms.push_back(g);
Modified: pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp
===================================================================
--- pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/collision_space/src/collision_space/environmentOctree.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan, Matei Ciocarlie */
+/** \author Ioan Sucan, Matei Ciocarlie */
#include <collision_space/environmentOctree.h>
@@ -148,7 +148,7 @@
return &m_octree;
}
-void collision_space::EnvironmentModelOctree::addPlane(double a, double b, double c, double d)
+void collision_space::EnvironmentModelOctree::addStaticPlane(double a, double b, double c, double d)
{
fprintf(stderr, "Octree collision checking does not support planes\n");
}
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/cnode.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
@@ -94,7 +94,7 @@
else
m_collisionSpace = new collision_space::EnvironmentModelODE();
m_collisionSpace->setSelfCollision(true);
- m_collisionSpace->addPlane(0.0, 0.0, 1.0, -0.01);
+ m_collisionSpace->addStaticPlane(0.0, 0.0, 1.0, -0.01);
m_sphereSize = 0.03;
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-09-05 17:07:53 UTC (rev 3981)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-09-05 17:19:44 UTC (rev 3982)
@@ -32,7 +32,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
-/** \Author Ioan Sucan */
+/** \author Ioan Sucan */
/**
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <stu...@us...> - 2008-09-05 18:36:59
|
Revision: 3986
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=3986&view=rev
Author: stuglaser
Date: 2008-09-05 18:37:10 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
Searches the correct path for the robot's .xml description file.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_actuators.cpp
pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parser.cpp
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_actuators.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_actuators.cpp 2008-09-05 18:05:23 UTC (rev 3985)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_actuators.cpp 2008-09-05 18:37:10 UTC (rev 3986)
@@ -73,13 +73,16 @@
return;
}
- // TODO: should look for the file relative to the path of the world file.
- std::string filename = robot->GetString("filename", "", 1);
+ std::string filename = robot->GetFilename("filename", "", 1);
printf("Loading %s\n", filename.c_str());
TiXmlDocument doc(filename);
- doc.LoadFile();
- assert(doc.RootElement());
+ if (!doc.LoadFile())
+ {
+ fprintf(stderr, "Error: Could not load the gazebo actuators plugin's configuration file: %s\n",
+ filename.c_str());
+ abort();
+ }
urdf::normalizeXml(doc.RootElement());
// Pulls out the list of actuators used in the robot configuration.
Modified: pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parser.cpp
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parser.cpp 2008-09-05 18:05:23 UTC (rev 3985)
+++ pkg/trunk/robot_descriptions/wg_robot_description_parser/src/parser.cpp 2008-09-05 18:37:10 UTC (rev 3986)
@@ -196,6 +196,10 @@
TiXmlElement *previous = NULL; // tracks the element before elt
+ //------------------------------------------------------------
+ // Zeroeth Pass
+
+ // - Replaces include elements with the desired file
while (elt)
{
if (elt->ValueStr() == std::string("include"))
@@ -243,7 +247,6 @@
// - Replaces insert_const_block elements with the corresponding xml tree.
// - Replaces const strings with the actual values.
// - Reduces mathematical expressions.
- // - Replaces include elements with the desired file
while (elt)
{
// Kills elt, if it's a const or const_block definition
@@ -270,30 +273,6 @@
elt = next_element(previous);
}
- // Replaces elt if it's an include tag.
- else if (elt->ValueStr() == std::string("include"))
- {
- std::string filename(elt->GetText());
-
- // FIXME: get path of current xml node and use relative path for includes
- std::string currentPath = getenv("MC_RESOURCE_PATH") ? getenv("MC_RESOURCE_PATH") : ".";
- if (currentPath!="") filename = (currentPath+"/")+filename;
-
- TiXmlDocument doc(filename);
- doc.LoadFile();
-
- if (!doc.RootElement())
- {
- fprintf(stderr, "Included file not found: %s\n", filename.c_str());
- elt->Parent()->RemoveChild(elt);
- }
- else
- {
- replaceReference(&elt, doc.RootElement()->FirstChild());
- }
-
- elt = next_element(previous);
- }
// Replaces the attributes of elt and the text inside elt if they
// have constants or expressions, and continues down the tree.
else
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2008-09-05 23:34:16
|
Revision: 4011
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4011&view=rev
Author: isucan
Date: 2008-09-05 23:34:27 +0000 (Fri, 05 Sep 2008)
Log Message:
-----------
maintaing two models of the robot: one in MAP frame the other in ROBOT frame
Modified Paths:
--------------
pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
Modified: pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h
===================================================================
--- pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-09-05 23:28:08 UTC (rev 4010)
+++ pkg/trunk/motion_planning/planning_node_util/include/planning_node_util/knode.h 2008-09-05 23:34:27 UTC (rev 4011)
@@ -92,7 +92,9 @@
{
m_urdf = NULL;
m_kmodel = NULL;
+ m_kmodelSimple = NULL;
m_robotState = NULL;
+ m_robotStateSimple = NULL;
m_node = node;
m_basePos[0] = m_basePos[1] = m_basePos[2] = 0.0;
m_robotModelName = robot_model;
@@ -110,8 +112,12 @@
delete m_urdf;
if (m_robotState)
delete m_robotState;
+ if (m_robotStateSimple)
+ delete m_robotStateSimple;
if (m_kmodel)
delete m_kmodel;
+ if (m_kmodelSimple)
+ delete m_kmodelSimple;
}
void setRobotDescriptionFromData(const char *data)
@@ -138,14 +144,22 @@
delete m_urdf;
if (m_kmodel)
delete m_kmodel;
+ if (m_kmodelSimple)
+ delete m_kmodelSimple;
m_urdf = file;
m_kmodel = new planning_models::KinematicModel();
m_kmodel->setVerbose(false);
m_kmodel->build(*file);
+
+ m_kmodelSimple = new planning_models::KinematicModel();
+ m_kmodelSimple->setVerbose(false);
+ m_kmodelSimple->build(*file);
m_robotState = m_kmodel->newStateParams();
m_robotState->setAll(0.0);
+ m_robotStateSimple = m_kmodelSimple->newStateParams();
+ m_robotStateSimple->setAll(0.0);
}
virtual void loadRobotDescription(void)
@@ -164,6 +178,8 @@
{
if (m_kmodel)
m_kmodel->defaultState();
+ if (m_kmodelSimple)
+ m_kmodelSimple->defaultState();
}
bool loadedRobot(void) const
@@ -232,6 +248,15 @@
double pos = m_mechanismState.joint_states[i].position;
m_robotState->setParams(&pos, m_mechanismState.joint_states[i].name);
}
+ }
+ if (m_robotStateSimple)
+ {
+ unsigned int n = m_mechanismState.get_joint_states_size();
+ for (unsigned int i = 0 ; i < n ; ++i)
+ {
+ double pos = m_mechanismState.joint_states[i].position;
+ m_robotStateSimple->setParams(&pos, m_mechanismState.joint_states[i].name);
+ }
}
m_haveMechanismState = true;
stateUpdate();
@@ -264,13 +289,18 @@
bool m_haveMechanismState;
robot_desc::URDF *m_urdf;
- planning_models::KinematicModel *m_kmodel;
+ planning_models::KinematicModel *m_kmodel; // MAP frame
+ planning_models::KinematicModel *m_kmodelSimple; // ROBOT frame
std::string m_robotModelName;
double m_basePos[3];
+ /** The complete robot state (MAP frame) */
planning_models::KinematicModel::StateParams *m_robotState;
bool m_haveState;
+
+ /** The robot state without the base position. The robot is at the origin (ROBOT frame) */
+ planning_models::KinematicModel::StateParams *m_robotStateSimple;
};
Modified: pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp
===================================================================
--- pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-09-05 23:28:08 UTC (rev 4010)
+++ pkg/trunk/world_models/world_3d_map/src/world_3d_map.cpp 2008-09-05 23:34:27 UTC (rev 4011)
@@ -182,6 +182,8 @@
planning_node_util::NodeRobotModel::stateUpdate();
if (m_kmodel)
m_kmodel->computeTransforms(m_robotState->getParams());
+ if (m_kmodelSimple)
+ m_kmodelSimple->computeTransforms(m_robotStateSimple->getParams());
}
void pointCloudCallback(void)
@@ -414,8 +416,9 @@
return cloudF;
}
- /* Remove invalid floating point values and strip channel iformation.
- * Also keep a certain ratio of the cloud information only */
+ /** Remove invalid floating point values and strip channel
+ * iformation. Also keep a certain ratio of the cloud information
+ * only. Works with pointclouds in FRAMEID_ROBOT or FRAMEID_MAP */
std_msgs::PointCloudFloat32* filter0(const std_msgs::PointCloudFloat32 &cloud, double frac = 1.0)
{
std_msgs::PointCloudFloat32 *copy = new std_msgs::PointCloudFloat32();
@@ -435,6 +438,9 @@
return copy;
}
+ /** Remove points from the cloud if the robot sees parts of
+ itself. Works for pointclouds in FRAMEID_ROBOT \todo make the
+ comment true, separate function in 2*/
std_msgs::PointCloudFloat32* filter1(const std_msgs::PointCloudFloat32 &cloud)
{
std_msgs::PointCloudFloat32 *copy = new std_msgs::PointCloudFloat32();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <ge...@us...> - 2008-09-08 16:14:12
|
Revision: 4033
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4033&view=rev
Author: gerkey
Date: 2008-09-08 16:14:19 +0000 (Mon, 08 Sep 2008)
Log Message:
-----------
modified Makefiles for new rospack syntax
Modified Paths:
--------------
pkg/trunk/3rdparty/estar/Makefile
pkg/trunk/3rdparty/libsunflower/Makefile
pkg/trunk/3rdparty/ogre/Makefile
pkg/trunk/drivers/robot/pr2/pr2Core/Makefile
pkg/trunk/nav/slam_gmapping/Makefile
pkg/trunk/simulators/nepumuk/Makefile
pkg/trunk/util/kinematics/libKinematics/Makefile
pkg/trunk/visualization/irrlicht_viewer/Makefile
pkg/trunk/visualization/pr2_gui/Makefile
Modified: pkg/trunk/3rdparty/estar/Makefile
===================================================================
--- pkg/trunk/3rdparty/estar/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/3rdparty/estar/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -23,7 +23,7 @@
UNPACK_CMD= tar xfz
BUILD_DIR= $(PWD)/build
INST_DIR= $(PWD)/local
-BOOST_DIR= `rospack --cflags-only-I boost`
+BOOST_DIR= `rospack cflags-only-I boost`
SVN_DIR= $(PWD)/estar-svn
SVN_REV= HEAD
Modified: pkg/trunk/3rdparty/libsunflower/Makefile
===================================================================
--- pkg/trunk/3rdparty/libsunflower/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/3rdparty/libsunflower/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -25,7 +25,7 @@
BUILD_DIR= $(PWD)/build
INST_DIR= $(PWD)/local
ESTAR_DIR= `rospack find estar`/local
-BOOST_DIR= `rospack --cflags-only-I boost`
+BOOST_DIR= `rospack cflags-only-I boost`
SVN_DIR= $(PWD)/sunflower-svn
SVN_REV= HEAD
Modified: pkg/trunk/3rdparty/ogre/Makefile
===================================================================
--- pkg/trunk/3rdparty/ogre/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/3rdparty/ogre/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -18,17 +18,17 @@
OISROOT = $(shell rospack find ois)/ois
CGROOT = $(shell rospack find Cg)/Cg
-CFLAGS = $(shell rospack export/cpp/cflags freeimage) \
- $(shell rospack export/cpp/cflags player) \
- $(shell rospack export/cpp/cflags opende) \
- $(shell rospack export/cpp/cflags ois) \
- $(shell rospack export/cpp/cflags Cg)
+CFLAGS = $(shell rospack --lang=cpp --attrib=cflags export freeimage) \
+ $(shell rospack --lang=cpp --attrib=cflags export player) \
+ $(shell rospack --lang=cpp --attrib=cflags export opende) \
+ $(shell rospack --lang=cpp --attrib=cflags export ois) \
+ $(shell rospack --lang=cpp --attrib=cflags export Cg)
-LFLAGS = $(shell rospack export/cpp/lflags freeimage) \
- $(shell rospack export/cpp/lflags player) \
- $(shell rospack export/cpp/lflags opende) \
- $(shell rospack export/cpp/lflags ois) \
- $(shell rospack export/cpp/lflags Cg)
+LFLAGS = $(shell rospack --lang=cpp --attrib=lflags export freeimage) \
+ $(shell rospack --lang=cpp --attrib=lflags export player) \
+ $(shell rospack --lang=cpp --attrib=lflags export opende) \
+ $(shell rospack --lang=cpp --attrib=lflags export ois) \
+ $(shell rospack --lang=cpp --attrib=lflags export Cg)
CONFIGURE_FLAGS = --with-arch=nocona --enable-release CXXFLAGS='-O3 -I$(FIROOT)/include -I$(OISROOT)/include -I$(CGROOT)/include' LDFLAGS='-Wl,-rpath,$(FIROOT)/lib,-rpath,$(OISROOT)/lib,-rpath,$(CGROOT)/lib -L$(FIROOT)/lib -L$(OISROOT)/lib -L$(CGROOT)/lib' CFLAGS='-O3 -I$(FIROOT)/include -I$(OISROOT)/include -I$(CGROOT)/include'
Modified: pkg/trunk/drivers/robot/pr2/pr2Core/Makefile
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2Core/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/drivers/robot/pr2/pr2Core/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -1,8 +1,8 @@
PKG = pr2Core
-CFLAGS = -g -Wall -Iinclude `rospack export/cpp/cflags $(PKG)`
+CFLAGS = -g -Wall -Iinclude `rospack --lang=cpp --attrib=cflags export $(PKG)`
-LDFLAGS = `rospack export/cpp/lflags $(PKG)`
+LDFLAGS = `rospack --lang=cpp --attrib=lflags export $(PKG)`
LIB =
Modified: pkg/trunk/nav/slam_gmapping/Makefile
===================================================================
--- pkg/trunk/nav/slam_gmapping/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/nav/slam_gmapping/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -2,8 +2,8 @@
CXX = g++
all: $(PKG)
-CFLAGS = -O3 -Wall `rospack export/cpp/cflags $(PKG)`
-LFLAGS = `rospack export/cpp/lflags $(PKG)`
+CFLAGS = -O3 -Wall `rospack --lang=cpp --attrib=cflags export $(PKG)`
+LFLAGS = `rospack --lang=cpp --attrib=lflags export $(PKG)`
slam_gmapping: slam_gmapping.cc
$(CXX) $(CFLAGS) -o $@ $< $(LFLAGS)
Modified: pkg/trunk/simulators/nepumuk/Makefile
===================================================================
--- pkg/trunk/simulators/nepumuk/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/simulators/nepumuk/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -29,7 +29,7 @@
INST_DIR= $(PWD)/local
ESTAR_DIR= `rospack find estar`/local
SFL_DIR= `rospack find libsunflower`/local
-BOOST_DIR= `rospack --cflags-only-I boost`
+BOOST_DIR= `rospack cflags-only-I boost`
SVN_DIR= $(PWD)/nepumuk-svn
SVN_REV= HEAD
Modified: pkg/trunk/util/kinematics/libKinematics/Makefile
===================================================================
--- pkg/trunk/util/kinematics/libKinematics/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/util/kinematics/libKinematics/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -1,10 +1,10 @@
PKG = libKinematics
-CFLAGS = -g -Wall -Iinclude $(shell rospack export/cpp/cflags $(PKG))
+CFLAGS = -g -Wall -Iinclude $(shell rospack --lang=cpp --attrib=cflags export $(PKG))
-LDFLAGS = $(shell rospack export/cpp/lflags newmat10)
+LDFLAGS = $(shell rospack --lang=cpp --attrib=lflags export newmat10)
-LFLAGS = $(shell rospack export/cpp/lflags $(PKG))
+LFLAGS = $(shell rospack --lang=cpp --attrib=lflags export $(PKG))
LIBK = lib/libKinematics.a
LIBIK = lib/libIk.a
Modified: pkg/trunk/visualization/irrlicht_viewer/Makefile
===================================================================
--- pkg/trunk/visualization/irrlicht_viewer/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/visualization/irrlicht_viewer/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -12,8 +12,8 @@
-CPPFLAGS = $(shell rospack export/cpp/cflags irrlicht_viewer)
-LDFLAGS = $(shell rospack export/cpp/lflags irrlicht_viewer)
+CPPFLAGS = $(shell rospack --lang=cpp --attrib=cflags export irrlicht_viewer)
+LDFLAGS = $(shell rospack --lang=cpp --attrib=lflags export irrlicht_viewer)
CUSTOM_NODES = $(shell ls CustomNodes/*.cc)
@@ -49,4 +49,4 @@
clouder: cloudGenerator.cc $(ILRENDER_LIB)
- $(CPP) $(CPPFLAGS) -o $@ $^ $(LDFLAGS)
\ No newline at end of file
+ $(CPP) $(CPPFLAGS) -o $@ $^ $(LDFLAGS)
Modified: pkg/trunk/visualization/pr2_gui/Makefile
===================================================================
--- pkg/trunk/visualization/pr2_gui/Makefile 2008-09-08 06:39:34 UTC (rev 4032)
+++ pkg/trunk/visualization/pr2_gui/Makefile 2008-09-08 16:14:19 UTC (rev 4033)
@@ -2,8 +2,8 @@
OUT = bin/pr2_gui
PKG = pr2_gui
-CFLAGS = -g `wx-config --cxxflags` $(shell rospack export/cpp/cflags pr2_gui)
-LFLAGS = `wx-config --libs` $(shell rospack export/cpp/lflags pr2_gui)
+CFLAGS = -g `wx-config --cxxflags` $(shell rospack --lang=cpp --attrib=cflags export pr2_gui)
+LFLAGS = `wx-config --libs` $(shell rospack --lang=cpp --attrib=lflags export pr2_gui)
all: $(SRC)
g++ $(SRC) $(CFLAGS) $(LFLAGS) -o $(OUT)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-09-08 21:46:47
|
Revision: 4048
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4048&view=rev
Author: hsujohnhsu
Date: 2008-09-08 21:46:56 +0000 (Mon, 08 Sep 2008)
Log Message:
-----------
controllers:
*joint_velocity_controllers: change joint_ to joint_state_ and robot_ to robot_state_
*add blank directory joint_controllers for upcoming migration from generic_controllers. also to move pid back to generic_controllers.
*updates to xml for new gripper.
Modified Paths:
--------------
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h
pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp
pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp
pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml
Added Paths:
-----------
pkg/trunk/controllers/joint_controllers/
pkg/trunk/controllers/joint_controllers/CMakeLists.txt
pkg/trunk/controllers/joint_controllers/Makefile
pkg/trunk/controllers/joint_controllers/include/
pkg/trunk/controllers/joint_controllers/include/joint_controllers/
pkg/trunk/controllers/joint_controllers/src/
pkg/trunk/controllers/joint_controllers/srv/
Modified: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-08 21:46:56 UTC (rev 4048)
@@ -87,8 +87,8 @@
* \param *joint The joint that is being controlled.
*/
- void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::Robot *robot);
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
+ void init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot_state);
+ bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
/*!
* \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
@@ -126,7 +126,7 @@
private:
mechanism::JointState *joint_state_;
- mechanism::RobotState *robot_; /**< Pointer to robot structure. */
+ mechanism::RobotState *robot_state_; /**< Pointer to robot structure. */
Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
double command_; /**< Last commanded position. */
@@ -163,7 +163,7 @@
void update();
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
+ bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
// Services
bool setCommand(generic_controllers::SetCommand::request &req,
Modified: pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp
===================================================================
--- pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/generic_controllers/src/joint_velocity_controller.cpp 2008-09-08 21:46:56 UTC (rev 4048)
@@ -41,7 +41,7 @@
ROS_REGISTER_CONTROLLER(JointVelocityController)
JointVelocityController::JointVelocityController()
-: joint_state_(NULL), robot_(NULL)
+: joint_state_(NULL), robot_state_(NULL)
{
// Initialize PID class
pid_controller_.initPid(0, 0, 0, 0, 0);
@@ -53,12 +53,39 @@
{
}
-bool JointVelocityController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+void JointVelocityController::init(double p_gain, double i_gain, double d_gain, double windup, double time, std::string name, mechanism::RobotState *robot_state)
{
- assert(robot);
- robot_ = robot;
- last_time_ = robot->hw_->current_time_;
+ assert(robot_state);
+ robot_state_ = robot_state;
+ last_time_ = robot_state->hw_->current_time_;
+ // FIXME: BRING BACK THIS FUNCTION CALL...
+ // const char *joint_name = j->Attribute("name");
+ // joint_state_ = robot_state_->getJointState(joint_name);
+ // if (joint_state_ == NULL)
+ // {
+ // std::cout << "JointVelocityController could not find joint named: " << joint_name << std::endl;
+ // fprintf(stderr, "JointVelocityController could not find joint named \"%s\"\n", joint_name);
+ // return false;
+ // }
+ // std::cout << "JointVelocityController loaded joint named: " << joint_name << std::endl;
+
+ // TiXmlElement *p = j->FirstChildElement("pid");
+ // if (p)
+ // pid_controller_.initXml(p);
+ // else
+ // fprintf(stderr, "JointVelocityController's config did not specify the default pid parameters.\n");
+
+ // return true;
+
+}
+
+bool JointVelocityController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
+{
+ assert(robot_state);
+ robot_state_ = robot_state;
+ last_time_ = robot_state->hw_->current_time_;
+
TiXmlElement *j = config->FirstChildElement("joint");
if (!j)
{
@@ -67,13 +94,14 @@
}
const char *joint_name = j->Attribute("name");
- int index = joint_name ? robot->model_->getJointIndex(joint_name) : NULL;
- if (index < 0)
+ joint_state_ = robot_state_->getJointState(joint_name);
+ if (joint_state_ == NULL)
{
+ std::cout << "JointVelocityController could not find joint named: " << joint_name << std::endl;
fprintf(stderr, "JointVelocityController could not find joint named \"%s\"\n", joint_name);
return false;
}
- joint_state_ = &robot_->joint_states_[index];
+ std::cout << "JointVelocityController loaded joint named: " << joint_name << std::endl;
TiXmlElement *p = j->FirstChildElement("pid");
if (p)
@@ -98,7 +126,7 @@
double JointVelocityController::getTime()
{
- return robot_->hw_->current_time_;
+ return robot_state_->hw_->current_time_;
}
// Return the measured joint velocity
@@ -115,7 +143,7 @@
void JointVelocityController::update()
{
double error(0);
- double time = robot_->hw_->current_time_;
+ double time = robot_state_->hw_->current_time_;
error = joint_state_->velocity_ - command_;
joint_state_->commanded_effort_ = pid_controller_.updatePid(error, time - last_time_);
@@ -169,7 +197,7 @@
return true;
}
-bool JointVelocityControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool JointVelocityControllerNode::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
@@ -180,7 +208,7 @@
return false;
}
- if (!c_->initXml(robot, config))
+ if (!c_->initXml(robot_state, config))
return false;
node->advertise_service(topic + "/set_command", &JointVelocityControllerNode::setCommand, this);
node->advertise_service(topic + "/get_actual", &JointVelocityControllerNode::getActual, this);
Added: pkg/trunk/controllers/joint_controllers/CMakeLists.txt
===================================================================
--- pkg/trunk/controllers/joint_controllers/CMakeLists.txt (rev 0)
+++ pkg/trunk/controllers/joint_controllers/CMakeLists.txt 2008-09-08 21:46:56 UTC (rev 4048)
@@ -0,0 +1,6 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(joint_controllers)
+genmsg()
+gensrv()
+rospack_add_library(joint_controllers src/joint_effort_controller.cpp src/joint_position_controller.cpp src/joint_velocity_controller.cpp src/ramp_effort_controller.cpp src/sine_sweep_controller.cpp src/joint_pd_controller.cpp)
Added: pkg/trunk/controllers/joint_controllers/Makefile
===================================================================
--- pkg/trunk/controllers/joint_controllers/Makefile (rev 0)
+++ pkg/trunk/controllers/joint_controllers/Makefile 2008-09-08 21:46:56 UTC (rev 4048)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Modified: pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/pr2_controllers/include/pr2_controllers/base_controller.h 2008-09-08 21:46:56 UTC (rev 4048)
@@ -81,7 +81,7 @@
JointVelocityController controller_; /** controller for the link */
- mechanism::JointState *joint_; /** pointer to joint in Robot structure corresponding to link */
+ mechanism::JointState *joint_state_; /** pointer to joint in Robot structure corresponding to link */
BaseParam *parent_; /** pointer to parent corresponding to link */
@@ -203,7 +203,7 @@
/*!
* \brief Robot representation
*/
- mechanism::RobotState* robot_;
+ mechanism::RobotState* robot_state_;
/*!
Modified: pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/pr2_controllers/src/arm_position_controller.cpp 2008-09-08 21:46:56 UTC (rev 4048)
@@ -268,6 +268,7 @@
{
c_->setJointPosCmd(req_goals_);
}
+
bool ArmPositionControllerNode::getJointPosCmd(pr2_controllers::GetJointPosCmd::request &req,
pr2_controllers::GetJointPosCmd::response &resp)
{
Modified: pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/controllers/pr2_controllers/src/base_controller.cpp 2008-09-08 21:46:56 UTC (rev 4048)
@@ -94,7 +94,7 @@
};
-void BaseController::init(std::vector<JointControlParam> jcp, mechanism::RobotState *robot)
+void BaseController::init(std::vector<JointControlParam> jcp, mechanism::RobotState *robot_state)
{
std::vector<JointControlParam>::iterator jcp_iter;
robot_desc::URDF::Link *link;
@@ -117,22 +117,27 @@
base_object.pos_.z = link->xyz[2];
base_object.name_ = joint_name;
base_object.parent_ = NULL;
- base_object.joint_ = robot->getJointState(joint_name);
+ base_object.joint_state_ = robot_state->getJointState(joint_name);
+ if (base_object.joint_state_==NULL)
+ std::cout << " unsuccessful getting joint state for " << joint_name << std::endl;
- abort();
- // TODO base_object.controller_.init(jcp_iter->p_gain,jcp_iter->i_gain,jcp_iter->d_gain,jcp_iter->windup,0.0,jcp_iter->joint_name,robot);
+ //abort();
+ base_object.controller_.init(jcp_iter->p_gain,jcp_iter->i_gain,jcp_iter->d_gain,jcp_iter->windup,0.0,jcp_iter->joint_name,robot_state);
if(joint_name.find("caster") != string::npos)
{
+ std::cout << " assigning casters " << joint_name << std::endl;
base_object.local_id_ = num_casters_;
base_casters_.push_back(base_object);
steer_angle_actual_.push_back(0);
steer_velocity_desired_.push_back(0);
num_casters_++;
-// cout << "base_casters" << ":: " << base_object;
+ cout << "base_casters" << ":: " << base_object;
}
+
if(joint_name.find("wheel") != string::npos)
{
+ std::cout << " assigning wheels " << joint_name << std::endl;
base_object.local_id_ = num_wheels_;
if(joint_name.find("_r_") != string::npos)
base_object.direction_multiplier_ = 1;
@@ -173,12 +178,12 @@
{
wheel_radius_ = DEFAULT_WHEEL_RADIUS;
}
- robot_ = robot;
+ robot_state_ = robot_state;
- last_time_ = robot_->hw_->current_time_;
+ last_time_ = robot_state_->hw_->current_time_;
}
-bool BaseController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool BaseController::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
std::cout << " base controller name: " << config->Attribute("name") << std::endl;
TiXmlElement *elt = config->FirstChildElement("controller");
@@ -227,14 +232,14 @@
// std::cout << " sub map : " << elt->Attribute("name") << std::endl;
elt = config->NextSiblingElement("map");
}
- init(jcp_vec,robot);
+ init(jcp_vec,robot_state);
return true;
}
void BaseController::getJointValues()
{
for(int i=0; i < num_casters_; i++)
- steer_angle_actual_[i] = base_casters_[i].joint_->position_;
+ steer_angle_actual_[i] = base_casters_[i].joint_state_->position_;
for(int i=0; i < num_wheels_; i++)
wheel_speed_actual_[i] = base_wheels_[i].controller_.getMeasuredVelocity();
@@ -251,7 +256,7 @@
double steer_angle;
for(int i=0; i < num_wheels_; i++)
{
- steer_angle = base_wheels_[i].parent_->joint_->position_;
+ steer_angle = base_wheels_[i].parent_->joint_state_->position_;
// res1 = rotate2D(base_wheels_[i].pos_,steer_angle);
// cout << "init position" << base_wheels_[i].pos_.x << " " << base_wheels_[i].pos_.y << " " << base_wheels_[i].pos_.z << endl;
res1 = base_wheels_[i].pos_.rot2D(steer_angle);
@@ -266,7 +271,7 @@
void BaseController::update()
{
- double current_time = robot_->hw_->current_time_;
+ double current_time = robot_state_->hw_->current_time_;
if(pthread_mutex_trylock(&base_controller_lock_)==0)
{
@@ -287,7 +292,7 @@
computeOdometry(current_time);
- if(odom_publish_counter_ > odom_publish_count_)
+ if(odom_publish_counter_ > odom_publish_count_) // FIXME: time based rate limiting
{
(ros::g_node)->publish("odom", odom_msg_);
odom_publish_counter_ = 0;
@@ -335,7 +340,7 @@
{
caster_2d_velocity.z = steer_velocity_desired_[base_wheels_[i].parent_->local_id_];
- steer_angle_actual = base_wheels_[i].parent_->joint_->position_;
+ steer_angle_actual = base_wheels_[i].parent_->joint_state_->position_;
wheel_point_velocity = computePointVelocity2D(base_wheels_position_[i],cmd_vel_);
// cout << "wheel_point_velocity" << wheel_point_velocity << ",pos::" << base_wheels_position_[i] << ",cmd::" << cmd_vel_ << endl;
@@ -416,12 +421,12 @@
return true;
}
-bool BaseControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
+bool BaseControllerNode::initXml(mechanism::RobotState *robot_state, TiXmlElement *config)
{
ros::node *node = ros::node::instance();
string prefix = config->Attribute("name");
- if(!c_->initXml(robot, config))
+ if(!c_->initXml(robot_state, config))
return false;
node->advertise_service(prefix + "/set_command", &BaseControllerNode::setCommand, this);
@@ -485,8 +490,8 @@
base_odom_position_ += base_odom_delta;
odom_msg_.header.frame_id = "FRAMEID_ODOM";
- odom_msg_.header.stamp.sec = (unsigned long)floor(robot_->hw_->current_time_);
- odom_msg_.header.stamp.nsec = (unsigned long)floor( 1e9 * ( robot_->hw_->current_time_ - odom_msg_.header.stamp.sec) );
+ odom_msg_.header.stamp.sec = (unsigned long)floor(robot_state_->hw_->current_time_);
+ odom_msg_.header.stamp.nsec = (unsigned long)floor( 1e9 * ( robot_state_->hw_->current_time_ - odom_msg_.header.stamp.sec) );
odom_msg_.pos.x = base_odom_position_.x;
odom_msg_.pos.y = base_odom_position_.y;
@@ -508,7 +513,7 @@
double steer_angle;
for(int i = 0; i < num_wheels_; i++) {
- steer_angle = base_wheels_[i].parent_->joint_->position_;
+ steer_angle = base_wheels_[i].parent_->joint_state_->position_;
A.element(i*2,0) = cos(steer_angle)*wheel_radius_*(wheel_speed_actual_[i]);
A.element(i*2+1,0) = sin(steer_angle)*wheel_radius_*(wheel_speed_actual_[i]);
// if(isnan(steer_angle))
@@ -566,7 +571,7 @@
std::ostream & controller::operator<<(std::ostream& mystream, const controller::BaseParam &bp)
{
- mystream << "BaseParam" << bp.name_ << endl << "position " << bp.pos_ << "id " << bp.local_id_ << endl << "joint " << bp.joint_->joint_->name_ << endl << endl;
+ mystream << "BaseParam" << bp.name_ << endl << "position " << bp.pos_ << "id " << bp.local_id_ << endl << "joint " << bp.joint_state_->joint_->name_ << endl << endl;
return mystream;
};
@@ -651,30 +656,30 @@
// Matrix D(3,1);
// for(int i = 0; i < NUM_CASTERS; i++) {
-// A.element(i*4,0) = cos(robot->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot->joint[i*3+1].velocity;
-// A.element(i*4+1,0) = sin(robot->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot->joint[i*3+1].velocity;
-// A.element(i*4+2,0) = cos(robot->joint[i*3].position) *WHEEL_RADIUS*robot->joint[i*3+2].velocity;
-// A.element(i*4+3,0) = sin(robot->joint[i*3].position)* WHEEL_RADIUS*robot->joint[i*3+2].velocity;
+// A.element(i*4,0) = cos(robot_state->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot_state->joint[i*3+1].velocity;
+// A.element(i*4+1,0) = sin(robot_state->joint[i*3].position) *WHEEL_RADIUS*((double)-1)*robot_state->joint[i*3+1].velocity;
+// A.element(i*4+2,0) = cos(robot_state->joint[i*3].position) *WHEEL_RADIUS*robot_state->joint[i*3+2].velocity;
+// A.element(i*4+3,0) = sin(robot_state->joint[i*3].position)* WHEEL_RADIUS*robot_state->joint[i*3+2].velocity;
// }
// /*
// for(int i = 0; i < (NUM_WHEELS + NUM_CASTERS); i++) {
-// printf("i: %i pos : %03f vel: %03f\n", i,robot->joint[i].position, robot->joint[i].velocity);
+// printf("i: %i pos : %03f vel: %03f\n", i,robot_state->joint[i].position, robot_state->joint[i].velocity);
// }
// */
// for(int i = 0; i < NUM_CASTERS; i++) {
// C.element(i*4, 0) = 1;
// C.element(i*4, 1) = 0;
-// C.element(i*4, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
+// C.element(i*4, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot_state->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
// C.element(i*4+1, 0) = 0;
// C.element(i*4+1, 1) = 1;
-// C.element(i*4+1, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
+// C.element(i*4+1, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2].x,CASTER_DRIVE_OFFSET[i*2].y,robot_state->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
// C.element(i*4+2, 0) = 1;
// C.element(i*4+2, 1) = 0;
-// C.element(i*4+2, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
+// C.element(i*4+2, 2) = -(Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot_state->joint[i*3].position).y + BASE_CASTER_OFFSET[i].y);
// C.element(i*4+3, 0) = 0;
// C.element(i*4+3, 1) = 1;
-// C.element(i*4+3, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
+// C.element(i*4+3, 2) = Rot2D(CASTER_DRIVE_OFFSET[i*2+1].x,CASTER_DRIVE_OFFSET[i*2+1].y,robot_state->joint[i*3].position).x + BASE_CASTER_OFFSET[i].x;
// }
// D = pseudoInverse(C)*A;
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers.xml 2008-09-08 21:46:56 UTC (rev 4048)
@@ -123,7 +123,7 @@
</controller>
<!-- Special gripper joint -->
<controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
- <joint name="gripper_left_joint">
+ <joint name="finger_l_left_joint">
<pid p="10" d="0" i="0" iClamp="0" />
<gripper_defaults effortLimit="100" velocityLimit="10" />
</joint>
@@ -175,7 +175,7 @@
</controller>
<!-- Special gripper joint -->
<controller name="gripper_right_controller" topic="gripper_right_controller" type="JointPositionControllerNode">
- <joint name="gripper_right_joint">
+ <joint name="finger_l_right_joint">
<pid p="10" d="0" i="0" iClamp="0" />
<gripper_defaults effortLimit="100" velocityLimit="10" />
</joint>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml 2008-09-08 21:46:45 UTC (rev 4047)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml 2008-09-08 21:46:56 UTC (rev 4048)
@@ -81,7 +81,7 @@
<explicitDampingCoefficient>1.0</explicitDampingCoefficient>
</joint>
<!-- Special gripper joint -->
- <joint name="gripper_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <joint name="finger_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
<left_proximal>finger_l_left_joint</left_proximal>
@@ -120,7 +120,7 @@
<explicitDampingCoefficient>1.0</explicitDampingCoefficient>
</joint>
<!-- Special gripper joint -->
- <joint name="gripper_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <joint name="finger_l_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
<left_proximal>finger_l_right_joint</left_proximal>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-09-08 23:46:17
|
Revision: 4062
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4062&view=rev
Author: hsujohnhsu
Date: 2008-09-08 23:46:26 +0000 (Mon, 08 Sep 2008)
Log Message:
-----------
final tweaks to get 2dnav-gazebo back online.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h 2008-09-08 23:41:46 UTC (rev 4061)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h 2008-09-08 23:46:26 UTC (rev 4062)
@@ -132,12 +132,14 @@
// for mechanism control
//---------------------------------------------------------------------
MechanismControl mc_;
- MechanismControl rmc_;
MechanismControlNode mcn_;
+ mechanism::RobotState *fake_state_;
+
void LoadMC(XMLConfigNode *node);
void UpdateMC();
+ void PublishROS();
void UpdateMCJoints();
void UpdateGazeboJoints();
@@ -200,7 +202,7 @@
{
std::string* name_;
std::vector<gazebo::Joint*> gaz_joints_;
- mechanism::JointState* rmc_joint_state_;
+ mechanism::JointState* fake_joint_state_;
double saturationTorque;
double explicitDampingCoefficient;
};
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-09-08 23:41:46 UTC (rev 4061)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-09-08 23:46:26 UTC (rev 4062)
@@ -53,7 +53,7 @@
GZ_REGISTER_DYNAMIC_CONTROLLER("test_actuators", TestActuators);
TestActuators::TestActuators(Entity *parent)
- : Controller(parent) , hw_(0), mc_(&hw_), rmc_(&hw_) , mcn_(&mc_)
+ : Controller(parent) , hw_(0), mc_(&hw_), fake_state_(NULL) , mcn_(&mc_)
{
this->parent_model_ = dynamic_cast<Model*>(this->parent);
@@ -167,22 +167,22 @@
//-----------------------------------------------------------------------------------------
TiXmlDocument *pr2_xml = new TiXmlDocument();
TiXmlDocument *controller_xml = new TiXmlDocument();
- TiXmlDocument *transmission_xml = new TiXmlDocument();
+ //TiXmlDocument *transmission_xml = new TiXmlDocument();
TiXmlDocument *actuator_xml = new TiXmlDocument();
std::string pr2_xml_filename = getenv("MC_RESOURCE_PATH"); pr2_xml_filename += "/"; pr2_xml_filename += node->GetString("robot_filename","",1);
std::string controller_xml_filename = getenv("MC_RESOURCE_PATH"); controller_xml_filename += "/"; controller_xml_filename += node->GetString("controller_filename","",1);
- std::string transmission_xml_filename = getenv("MC_RESOURCE_PATH"); transmission_xml_filename += "/"; transmission_xml_filename += node->GetString("transmission_filename","",1);
+ //std::string transmission_xml_filename = getenv("MC_RESOURCE_PATH"); transmission_xml_filename += "/"; transmission_xml_filename += node->GetString("transmission_filename","",1);
std::string actuator_xml_filename = getenv("MC_RESOURCE_PATH"); actuator_xml_filename += "/"; actuator_xml_filename += node->GetString("actuator_filename","",1);
std::cout << " pr2 robot xml file name: " << pr2_xml_filename << std::endl;
std::cout << " controller file name: " << controller_xml_filename << std::endl;
- std::cout << " transmission file name: " << transmission_xml_filename << std::endl;
+ //std::cout << " transmission file name: " << transmission_xml_filename << std::endl;
std::cout << " actuator file name: " << actuator_xml_filename << std::endl;
pr2_xml ->LoadFile(pr2_xml_filename);
controller_xml ->LoadFile(controller_xml_filename);
- transmission_xml->LoadFile(transmission_xml_filename);
+ //transmission_xml->LoadFile(transmission_xml_filename);
actuator_xml ->LoadFile(actuator_xml_filename);
urdf::normalizeXml( pr2_xml->RootElement() );
@@ -243,8 +243,9 @@
//
//-----------------------------------------------------------------------------------------
mcn_.initXml(pr2_xml->FirstChildElement("robot"));
- rmc_.initXml(pr2_xml->FirstChildElement("robot"));
+ fake_state_ = new mechanism::RobotState(&mc_.model_, &hw_);
+
//-----------------------------------------------------------------------------------------
//
// how the mechanism joints relate to the gazebo_joints
@@ -264,7 +265,7 @@
// add a link to the mechanism control joint
- gj->rmc_joint_state_ = rmc_.state_->getJointState(*joint_name);
+ gj->fake_joint_state_ = fake_state_->getJointState(*joint_name);
// read gazebo specific joint properties
gj->saturationTorque = jNode->GetDouble("saturationTorque",0.0,0);
@@ -291,16 +292,6 @@
//-----------------------------------------------------------------------------------------
//
- // TRANSMISSION XML
- //
- // make mc parse xml for transmissions
- //
- //-----------------------------------------------------------------------------------------
- mcn_.initXml(transmission_xml->FirstChildElement("robot"));
- rmc_.initXml(transmission_xml->FirstChildElement("robot"));
-
- //-----------------------------------------------------------------------------------------
- //
// CONTROLLER XML
//
// spawn controllers
@@ -320,12 +311,6 @@
mc_.spawnController(*controller_type,
*controller_name,
zit);
-
- std::cout << " adding to rmc_ " << *controller_name << "(" << *controller_type << ")" << std::endl;
- rmc_.spawnController(*controller_type,
- *controller_name,
- zit);
-
}
}
@@ -365,76 +350,18 @@
lastRealTime = currentRealTime;
}
- this->lock.lock();
- /***************************************************************/
- /* */
- /* publish time to ros */
- /* */
- /***************************************************************/
- timeMsg.rostime.sec = (unsigned long)floor(hw_.current_time_);
- timeMsg.rostime.nsec = (unsigned long)floor( 1e9 * ( hw_.current_time_ - timeMsg.rostime.sec) );
- rosnode_->publish("time",timeMsg);
+ PublishROS();
- /***************************************************************/
- /* */
- /* object position */
- /* FIXME: move this to the P3D plugin (update P3D required) */
- /* */
- /***************************************************************/
- //this->PR2Copy->GetObjectPositionActual(&x,&y,&z,&roll,&pitch,&yaw);
- //this->objectPosMsg.x = x;
- //this->objectPosMsg.y = y;
- //this->objectPosMsg.z = z;
- //rosnode_->publish("object_position", this->objectPosMsg);
-
-
-
- /* get left arm position */
- if( mc_.state_->getJointState("shoulder_pan_left_joint") ) larm.turretAngle = mc_.state_->getJointState("shoulder_pan_left_joint") ->position_;
- if( mc_.state_->getJointState("shoulder_pitch_left_joint") ) larm.shoulderLiftAngle = mc_.state_->getJointState("shoulder_pitch_left_joint")->position_;
- if( mc_.state_->getJointState("upperarm_roll_left_joint") ) larm.upperarmRollAngle = mc_.state_->getJointState("upperarm_roll_left_joint") ->position_;
- if( mc_.state_->getJointState("elbow_flex_left_joint") ) larm.elbowAngle = mc_.state_->getJointState("elbow_flex_left_joint") ->position_;
- if( mc_.state_->getJointState("forearm_roll_left_joint") ) larm.forearmRollAngle = mc_.state_->getJointState("forearm_roll_left_joint") ->position_;
- if( mc_.state_->getJointState("wrist_flex_left_joint") ) larm.wristPitchAngle = mc_.state_->getJointState("wrist_flex_left_joint") ->position_;
- if( mc_.state_->getJointState("gripper_roll_left_joint") ) larm.wristRollAngle = mc_.state_->getJointState("gripper_roll_left_joint") ->position_;
- if( mc_.state_->getJointState("gripper_left_joint") ) larm.gripperForceCmd = mc_.state_->getJointState("gripper_left_joint") ->applied_effort_;
- if( mc_.state_->getJointState("gripper_left_joint") ) larm.gripperGapCmd = mc_.state_->getJointState("gripper_left_joint") ->position_;
- rosnode_->publish("left_pr2arm_pos", larm);
- /* get right arm position */
- if( mc_.state_->getJointState("shoulder_pan_right_joint") ) rarm.turretAngle = mc_.state_->getJointState("shoulder_pan_right_joint") ->position_;
- if( mc_.state_->getJointState("shoulder_pitch_right_joint") ) rarm.shoulderLiftAngle = mc_.state_->getJointState("shoulder_pitch_right_joint")->position_;
- if( mc_.state_->getJointState("upperarm_roll_right_joint") ) rarm.upperarmRollAngle = mc_.state_->getJointState("upperarm_roll_right_joint") ->position_;
- if( mc_.state_->getJointState("elbow_flex_right_joint") ) rarm.elbowAngle = mc_.state_->getJointState("elbow_flex_right_joint") ->position_;
- if( mc_.state_->getJointState("forearm_roll_right_joint") ) rarm.forearmRollAngle = mc_.state_->getJointState("forearm_roll_right_joint") ->position_;
- if( mc_.state_->getJointState("wrist_flex_right_joint") ) rarm.wristPitchAngle = mc_.state_->getJointState("wrist_flex_right_joint") ->position_;
- if( mc_.state_->getJointState("gripper_roll_right_joint") ) rarm.wristRollAngle = mc_.state_->getJointState("gripper_roll_right_joint") ->position_;
- if( mc_.state_->getJointState("gripper_right_joint") ) rarm.gripperForceCmd = mc_.state_->getJointState("gripper_right_joint") ->applied_effort_;
- if( mc_.state_->getJointState("gripper_right_joint") ) rarm.gripperGapCmd = mc_.state_->getJointState("gripper_right_joint") ->position_;
- rosnode_->publish("right_pr2arm_pos", rarm);
-
- PublishFrameTransforms();
-
- this->lock.unlock();
-
//---------------------------------------------------------------------
// Real time update calls to mechanism control
// this is what the hard real time loop does,
// minus the tick() call to etherCAT
//---------------------------------------------------------------------
- //
- // step through all controllers in the Robot_controller
+ // fetch joint info into fake_state_ from gazebo joints
UpdateMCJoints();
-
-
// push reverse_mech_joint_ stuff back toward actuators
- for (unsigned int i=0; i < rmc_.model_.transmissions_.size(); i++)
- {
- rmc_.state_->propagateStateBackwards();
- rmc_.state_->propagateEffort();
- // std::cout << " applying reverse transmisison : "
- // << dynamic_cast<mechanism::SimpleTransmission*>(rmc_.model_.transmissions_[i])->name_
- // << " " << std::endl;
- }
+ fake_state_->propagateStateBackwards();
+ fake_state_->propagateEffort();
// -------------------------------------------------------------------------------------------------
@@ -497,13 +424,10 @@
// - -
// -------------------------------------------------------------------------------------------------
// propagate actuator data back to reverse-joints
- for (unsigned int i=0; i < rmc_.model_.transmissions_.size(); i++)
- {
- // assign reverse joint states from actuator states
- rmc_.state_->propagateState();
- // assign joint effort
- rmc_.state_->propagateEffortBackwards();
- }
+ // assign reverse joint states from actuator states
+ fake_state_->propagateState();
+ // assign joint effort
+ fake_state_->propagateEffortBackwards();
UpdateGazeboJoints();
@@ -512,7 +436,61 @@
}
+ void TestActuators::PublishROS()
+ {
+ this->lock.lock();
+ /***************************************************************/
+ /* */
+ /* publish time to ros */
+ /* */
+ /***************************************************************/
+ timeMsg.rostime.sec = (unsigned long)floor(hw_.current_time_);
+ timeMsg.rostime.nsec = (unsigned long)floor( 1e9 * ( hw_.current_time_ - timeMsg.rostime.sec) );
+ rosnode_->publish("time",timeMsg);
+ /***************************************************************/
+ /* */
+ /* object position */
+ /* FIXME: move this to the P3D plugin (update P3D required) */
+ /* */
+ /***************************************************************/
+ //this->PR2Copy->GetObjectPositionActual(&x,&y,&z,&roll,&pitch,&yaw);
+ //this->objectPosMsg.x = x;
+ //this->objectPosMsg.y = y;
+ //this->objectPosMsg.z = z;
+ //rosnode_->publish("object_position", this->objectPosMsg);
+
+
+
+ /* get left arm position */
+ if( mc_.state_->getJointState("shoulder_pan_left_joint") ) larm.turretAngle = mc_.state_->getJointState("shoulder_pan_left_joint") ->position_;
+ if( mc_.state_->getJointState("shoulder_pitch_left_joint") ) larm.shoulderLiftAngle = mc_.state_->getJointState("shoulder_pitch_left_joint")->position_;
+ if( mc_.state_->getJointState("upperarm_roll_left_joint") ) larm.upperarmRollAngle = mc_.state_->getJointState("upperarm_roll_left_joint") ->position_;
+ if( mc_.state_->getJointState("elbow_flex_left_joint") ) larm.elbowAngle = mc_.state_->getJointState("elbow_flex_left_joint") ->position_;
+ if( mc_.state_->getJointState("forearm_roll_left_joint") ) larm.forearmRollAngle = mc_.state_->getJointState("forearm_roll_left_joint") ->position_;
+ if( mc_.state_->getJointState("wrist_flex_left_joint") ) larm.wristPitchAngle = mc_.state_->getJointState("wrist_flex_left_joint") ->position_;
+ if( mc_.state_->getJointState("gripper_roll_left_joint") ) larm.wristRollAngle = mc_.state_->getJointState("gripper_roll_left_joint") ->position_;
+ if( mc_.state_->getJointState("gripper_left_joint") ) larm.gripperForceCmd = mc_.state_->getJointState("gripper_left_joint") ->applied_effort_;
+ if( mc_.state_->getJointState("gripper_left_joint") ) larm.gripperGapCmd = mc_.state_->getJointState("gripper_left_joint") ->position_;
+ rosnode_->publish("left_pr2arm_pos", larm);
+ /* get right arm position */
+ if( mc_.state_->getJointState("shoulder_pan_right_joint") ) rarm.turretAngle = mc_.state_->getJointState("shoulder_pan_right_joint") ->position_;
+ if( mc_.state_->getJointState("shoulder_pitch_right_joint") ) rarm.shoulderLiftAngle = mc_.state_->getJointState("shoulder_pitch_right_joint")->position_;
+ if( mc_.state_->getJointState("upperarm_roll_right_joint") ) rarm.upperarmRollAngle = mc_.state_->getJointState("upperarm_roll_right_joint") ->position_;
+ if( mc_.state_->getJointState("elbow_flex_right_joint") ) rarm.elbowAngle = mc_.state_->getJointState("elbow_flex_right_joint") ->position_;
+ if( mc_.state_->getJointState("forearm_roll_right_joint") ) rarm.forearmRollAngle = mc_.state_->getJointState("forearm_roll_right_joint") ->position_;
+ if( mc_.state_->getJointState("wrist_flex_right_joint") ) rarm.wristPitchAngle = mc_.state_->getJointState("wrist_flex_right_joint") ->position_;
+ if( mc_.state_->getJointState("gripper_roll_right_joint") ) rarm.wristRollAngle = mc_.state_->getJointState("gripper_roll_right_joint") ->position_;
+ if( mc_.state_->getJointState("gripper_right_joint") ) rarm.gripperForceCmd = mc_.state_->getJointState("gripper_right_joint") ->applied_effort_;
+ if( mc_.state_->getJointState("gripper_right_joint") ) rarm.gripperGapCmd = mc_.state_->getJointState("gripper_right_joint") ->position_;
+ rosnode_->publish("right_pr2arm_pos", rarm);
+
+ PublishFrameTransforms();
+
+ this->lock.unlock();
+ }
+
+
void TestActuators::UpdateGazeboJoints()
{
// -------------------------------------------------------------------------------------------------
@@ -531,7 +509,7 @@
if (gjs)
{
double dampForce = -(*gji)->explicitDampingCoefficient * gjs->GetPositionRate();
- gjs->SetSliderForce( (*gji)->rmc_joint_state_->commanded_effort_+dampForce);
+ gjs->SetSliderForce( (*gji)->fake_joint_state_->commanded_effort_+dampForce);
break;
}
}
@@ -541,8 +519,8 @@
if (gjh)
{
double dampForce = -(*gji)->explicitDampingCoefficient * gjh->GetAngleRate();
- gjh->SetTorque( (*gji)->rmc_joint_state_->commanded_effort_+dampForce);
- //std::cout << " hinge " << *((*gji)->name_) << " torque: " << (*gji)->rmc_joint_state_->commanded_effort_ << " damping " << dampForce << std::endl;
+ gjh->SetTorque( (*gji)->fake_joint_state_->commanded_effort_+dampForce);
+ //std::cout << " hinge " << *((*gji)->name_) << " torque: " << (*gji)->fake_joint_state_->commanded_effort_ << " damping " << dampForce << std::endl;
break;
}
}
@@ -565,18 +543,18 @@
case gazebo::Joint::SLIDER:
{
gazebo::SliderJoint* gjs = dynamic_cast<gazebo::SliderJoint*>((*gji)->gaz_joints_[0]);
- (*gji)->rmc_joint_state_->position_ = gjs->GetPosition();
- (*gji)->rmc_joint_state_->velocity_ = gjs->GetPositionRate();
- (*gji)->rmc_joint_state_->applied_effort_ = (*gji)->rmc_joint_state_->commanded_effort_;
+ (*gji)->fake_joint_state_->position_ = gjs->GetPosition();
+ (*gji)->fake_joint_state_->velocity_ = gjs->GetPositionRate();
+ (*gji)->fake_joint_state_->applied_effort_ = (*gji)->fake_joint_state_->commanded_effort_;
break;
}
case gazebo::Joint::HINGE:
{
gazebo::HingeJoint* gjh = dynamic_cast<gazebo::HingeJoint*>((*gji)->gaz_joints_[0]);
- (*gji)->rmc_joint_state_->position_ = gjh->GetAngle();
- (*gji)->rmc_joint_state_->velocity_ = gjh->GetAngleRate();
- (*gji)->rmc_joint_state_->applied_effort_ = (*gji)->rmc_joint_state_->commanded_effort_;
- //std::cout << " hinge " << *((*gji)->name_) << " angle " << (*gji)->rmc_joint_state_->position_ << std::endl;
+ (*gji)->fake_joint_state_->position_ = gjh->GetAngle();
+ (*gji)->fake_joint_state_->velocity_ = gjh->GetAngleRate();
+ (*gji)->fake_joint_state_->applied_effort_ = (*gji)->fake_joint_state_->commanded_effort_;
+ //std::cout << " hinge " << *((*gji)->name_) << " angle " << (*gji)->fake_joint_state_->position_ << std::endl;
break;
}
case gazebo::Joint::HINGE2:
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml 2008-09-08 23:41:46 UTC (rev 4061)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/gazebo_joints.xml 2008-09-08 23:46:26 UTC (rev 4062)
@@ -80,15 +80,23 @@
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>1.0</explicitDampingCoefficient>
</joint>
- <!-- Special gripper joint -->
- <joint name="finger_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <!-- Special gripper joint -->
+ <joint name="finger_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
- <left_proximal>finger_l_left_joint</left_proximal>
- <left_distal>finger_tip_l_left_joint</left_distal>
- <right_proximal>finger_r_left_joint</right_proximal>
- <right_distal>finger_tip_r_left_joint</right_distal>
</joint>
+ <joint name="finger_r_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+ <joint name="finger_tip_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+ <joint name="finger_tip_r_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
<!-- ========================================= -->
<!-- right arm array -->
<joint name="shoulder_pan_right_joint" >
@@ -120,14 +128,22 @@
<explicitDampingCoefficient>1.0</explicitDampingCoefficient>
</joint>
<!-- Special gripper joint -->
- <joint name="finger_l_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <joint name="finger_l_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
- <left_proximal>finger_l_right_joint</left_proximal>
- <left_distal>finger_tip_l_right_joint</left_distal>
- <right_proximal>finger_r_right_joint</right_proximal>
- <right_distal>finger_tip_r_right_joint</right_distal>
</joint>
+ <joint name="finger_r_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+ <joint name="finger_tip_l_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+ <joint name="finger_tip_r_right_joint" gripper_controller="gripper_right_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
<!-- head and above array -->
<joint name="head_pan_joint" >
<saturationTorque>100</saturationTorque>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-09-09 00:21:06
|
Revision: 4065
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4065&view=rev
Author: hsujohnhsu
Date: 2008-09-09 00:21:15 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
re-enable headless demo.
Modified Paths:
--------------
pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-headless.xml
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h
pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
Modified: pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-headless.xml
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-headless.xml 2008-09-08 23:58:52 UTC (rev 4064)
+++ pkg/trunk/demos/2dnav-gazebo/2dnav-gazebo-headless.xml 2008-09-09 00:21:15 UTC (rev 4065)
@@ -7,9 +7,9 @@
<node pkg="nav_view" type="nav_view" respawn="false" output="screen" />
<!-- for visualization -->
- <node pkg="wx_camera_panel" type="standalone_camera.py" args="-i PTZR_image -s PTZR_state -c PTZR_cmd -n PTZR" respawn="false" output="screen" />
- <node pkg="laser_view" type="laser_view" args="scan:=tilt_scan" respawn="false" output="screen" />
- <!--node pkg="ogre_visualizer" type="visualizer_test" respawn="false" output="screen" /--><!-- way too slow, why? -->
+ <node pkg="wx_camera_panel" type="camera_test" args="" respawn="true" output="screen" />
+ <node pkg="laser_view" type="laser_view" args="scan:=tilt_scan" respawn="true" output="screen" />
+ <node pkg="ogre_visualizer" type="visualizer_test" respawn="true" output="screen" />
<!--node pkg="wxpy_ros" type="ros_panel" respawn="false" output="screen" /--><!-- does not start correctly-->
<!-- for manual control -->
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h 2008-09-08 23:58:52 UTC (rev 4064)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/test_actuators.h 2008-09-09 00:21:15 UTC (rev 4065)
@@ -148,39 +148,9 @@
//std::string xml_file; // xml filename for the robot
//TiXmlElement *root;
- // JMH: as far as I know, this parsing in mech-control is not functional yet,
- // so I am going to use either:
- // 1. Ioan's parser
- // 2. My own parser to fill out mappings
- //
- // steps are defined below
- // 1. fill in MechanismControl->Robot->Joint (defines robot)
- //std::vector<mechanism::Joint*> mech_joints_;
- //std::vector<mechanism::Transmission*> transmissions_;
- //std::vector<std::string> actuator_names_;
- //std::vector<gazebo::Joint*> gazebo_joints_;
HardwareInterface hw_;
- // 2. fill in HardwareInterface
- // actuators_ is a vector
- // current_time_ is a double
- // 3. fill in MechanismControl->Robot->Transmission->Actuators->ActuatorState (define transmissions)
- // fill in MechanismControl->Robot->Transmission->Actuators->ActuatorCommand
- // 4. fill in MechanismControl->JointController (define controllers)
- // fill in MechanismControl->JointController->*Joints (define joints controlled)
- //
//---------------------------------------------------------------------
- // for gazebo hardware
- //---------------------------------------------------------------------
- // Each joint in joints_ corresponds to the joint with the same
- // index in mech_joints_. The mech_joints_ vector exists so that
- // each transmission has a mechanism::Joint to write to, because it
- // would be best if the transmissions did not depend on Gazebo
- // objects.
- // define a map to keep track of joints mapping from mech to gaz
- // struct robot_to_gazebo_joints_
-
- //---------------------------------------------------------------------
// --
// BELOW IS JOHN'S VERSION OF MECHANISM CONTROL, WAITING ... FOR --
// THE ACTUAL ONE TO BE FUNCTIONAL. --
@@ -210,20 +180,8 @@
double currentTime;
double lastTime;
- // for storing transmission xml
- // struct Robot_transmission_
- // {
- // std::string name;
- // mechanism::SimpleTransmission simple_transmission;
- // gazebo::Joint* gazebo_joints_;
- // };
- //std::vector<Robot_transmission_> robot_transmissions_;
- //std::vector<Robot_transmission_> reverse_robot_transmissions_;
-
-
-
//------------------------------------------------------------
// offsets for frame transform
//------------------------------------------------------------
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-09-08 23:58:52 UTC (rev 4064)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-09-09 00:21:15 UTC (rev 4065)
@@ -75,11 +75,6 @@
// uses info from wg_robot_description_parser/send.xml
std::string pr2Content;
- // get pr2.xml for Ioan's parser
- //rosnode_->get_param("robotdesc/pr2",pr2Content);
- // parse the big pr2.xml string from ros, or use below so we don't need to roslaunch send.xml
- //pr2Description.loadString(pr2Content.c_str());
-
AdvertiseSubscribeMessages();
}
@@ -167,27 +162,22 @@
//-----------------------------------------------------------------------------------------
TiXmlDocument *pr2_xml = new TiXmlDocument();
TiXmlDocument *controller_xml = new TiXmlDocument();
- //TiXmlDocument *transmission_xml = new TiXmlDocument();
TiXmlDocument *actuator_xml = new TiXmlDocument();
std::string pr2_xml_filename = getenv("MC_RESOURCE_PATH"); pr2_xml_filename += "/"; pr2_xml_filename += node->GetString("robot_filename","",1);
std::string controller_xml_filename = getenv("MC_RESOURCE_PATH"); controller_xml_filename += "/"; controller_xml_filename += node->GetString("controller_filename","",1);
- //std::string transmission_xml_filename = getenv("MC_RESOURCE_PATH"); transmission_xml_filename += "/"; transmission_xml_filename += node->GetString("transmission_filename","",1);
std::string actuator_xml_filename = getenv("MC_RESOURCE_PATH"); actuator_xml_filename += "/"; actuator_xml_filename += node->GetString("actuator_filename","",1);
std::cout << " pr2 robot xml file name: " << pr2_xml_filename << std::endl;
std::cout << " controller file name: " << controller_xml_filename << std::endl;
- //std::cout << " transmission file name: " << transmission_xml_filename << std::endl;
std::cout << " actuator file name: " << actuator_xml_filename << std::endl;
pr2_xml ->LoadFile(pr2_xml_filename);
controller_xml ->LoadFile(controller_xml_filename);
- //transmission_xml->LoadFile(transmission_xml_filename);
actuator_xml ->LoadFile(actuator_xml_filename);
urdf::normalizeXml( pr2_xml->RootElement() );
//urdf::normalizeXml( controller_xml->RootElement() );
- //urdf::normalizeXml( transmission_xml->RootElement() );
//urdf::normalizeXml( actuator_xml->RootElement() );
//-------------------------------------------------------------------------------------------
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-08 23:58:52 UTC (rev 4064)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-09 00:21:15 UTC (rev 4065)
@@ -12,12 +12,11 @@
<controller:test_actuators name="test_actuators" plugin="libtest_actuators.so">
<updateRate>100.0</updateRate>
+ <!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
<include>gazebo_joints.xml</include>
-
<robot_filename>pr2_test_actuators.xml</robot_filename>
<controller_filename>controllers.xml</controller_filename>
<actuator_filename>actuators.xml</actuator_filename>
- <transmission_filename>transmissions.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-08 23:58:52 UTC (rev 4064)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-09 00:21:15 UTC (rev 4065)
@@ -12,12 +12,11 @@
<controller:test_actuators name="test_actuators" plugin="libtest_actuators.so">
<updateRate>1000.0</updateRate>
+ <!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
<include>gazebo_joints.xml</include>
-
<robot_filename>pr2_test_actuators.xml</robot_filename>
<controller_filename>controllers.xml</controller_filename>
<actuator_filename>actuators.xml</actuator_filename>
- <transmission_filename>transmissions.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-09-09 02:49:22
|
Revision: 4076
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4076&view=rev
Author: hsujohnhsu
Date: 2008-09-09 02:49:31 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
updates to make pr2_arm_test work as well. (no <limit> tag == no joint added to model_).
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test_headless.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/gazebo_joints_arm_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test_headless.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_headless.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_tjh.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/transmissions_arm_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_gazebo_single_link.xml
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/test_actuators.cpp 2008-09-09 02:49:31 UTC (rev 4076)
@@ -256,6 +256,7 @@
// add a link to the mechanism control joint
gj->fake_joint_state_ = fake_state_->getJointState(*joint_name);
+ if (gj->fake_joint_state_==NULL) {std::cout << " no joint name found in joint state " << *joint_name << std::endl; abort();}; // make sure no NULL fake_joint_state_
// read gazebo specific joint properties
gj->saturationTorque = jNode->GetDouble("saturationTorque",0.0,0);
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm_test.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_arm_test.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -48,10 +48,10 @@
</joint>
</controller>
</controller>
- <!-- Special gripper joint -->
- <controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
- <joint name="gripper_left_joint">
- <pid p="1" d="0" i="0" iClamp="0" />
+ <!-- Special gripper joint -->
+ <controller name="gripper_left_controller" topic="gripper_left_controller" type="JointPositionControllerNode">
+ <joint name="finger_l_left_joint">
+ <pid p="10" d="0" i="0" iClamp="0" />
<gripper_defaults effortLimit="100" velocityLimit="10" />
</joint>
</controller>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -17,7 +17,6 @@
<robot_filename>pr2_arm_test.xml</robot_filename>
<controller_filename>controllers_arm_test.xml</controller_filename>
<actuator_filename>actuators_arm_test.xml</actuator_filename>
- <transmission_filename>transmissions_arm_test.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test_headless.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/controllers_gazebo_arm_test_headless.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -17,7 +17,6 @@
<robot_filename>pr2_arm_test.xml</robot_filename>
<controller_filename>controllers_arm_test.xml</controller_filename>
<actuator_filename>actuators_arm_test.xml</actuator_filename>
- <transmission_filename>transmissions_arm_test.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/gazebo_joints_arm_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/gazebo_joints_arm_test.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/gazebo_joints_arm_test.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -30,14 +30,25 @@
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
</joint>
<!-- Special gripper joint -->
- <joint name="gripper_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <joint name="finger_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
<saturationTorque>100</saturationTorque>
<explicitDampingCoefficient>0.1</explicitDampingCoefficient>
- <left_proximal>finger_l_left_joint</left_proximal>
- <left_distal>finger_tip_l_left_joint</left_distal>
- <right_proximal>finger_r_left_joint</right_proximal>
- <right_distal>finger_tip_r_left_joint</right_distal>
</joint>
+ <joint name="finger_r_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+ <joint name="finger_tip_l_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+
+ <joint name="finger_tip_r_left_joint" gripper_controller="gripper_left_controller" abstract="gripper" effortLimit="1000" velocityLimit="100">
+ <saturationTorque>100</saturationTorque>
+ <explicitDampingCoefficient>0.1</explicitDampingCoefficient>
+ </joint>
+
+
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -414,6 +414,7 @@
<const_block name="pr2_finger_r_joint">
<axis xyz=" 0 0 1 " /> <!-- direction of the joint in a global coordinate frame -->
<anchor xyz="0 0 0 " /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit effort="100" velocity="5" />
<calibration values="1.5 -1 " /> <!-- Calibration stop/flag indicating location and then direction -->
</const_block>
@@ -447,6 +448,7 @@
<const_block name="pr2_finger_tip_r_joint">
<axis xyz=" 0 0 1 " /> <!-- direction of the joint in a global coordinate frame -->
<anchor xyz="0 0 0 " /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit effort="100" velocity="5" />
<calibration values="1.5 -1 " /> <!-- Calibration stop/flag indicating location and then direction -->
</const_block>
@@ -943,13 +945,13 @@
<include>groups_arm_test.xml</include>
+
+ <!-- new definitions for mechanism controls - JMH -->
+ <include>controllers_arm_test.xml</include>
+ <include>actuators_arm_test.xml</include>
+ <include>transmissions_arm_test.xml</include>
+
<!-- controllers for gazebo -->
<include>controllers_gazebo_arm_test.xml</include>
-
- <!-- new definitions for mechanism controls - JMH -->
- <!--
- <include>controllers.xml</include>
- <include>actuators.xml</include>
- <include>transmissions.xml</include>
- -->
+
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test_headless.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/pr2_arm_test_headless.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -414,6 +414,7 @@
<const_block name="pr2_finger_r_joint">
<axis xyz=" 0 0 1 " /> <!-- direction of the joint in a global coordinate frame -->
<anchor xyz="0 0 0 " /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit effort="100" velocity="5" />
<calibration values="1.5 -1 " /> <!-- Calibration stop/flag indicating location and then direction -->
</const_block>
@@ -447,6 +448,7 @@
<const_block name="pr2_finger_tip_r_joint">
<axis xyz=" 0 0 1 " /> <!-- direction of the joint in a global coordinate frame -->
<anchor xyz="0 0 0 " /> <!-- point on the joint relative to the parent's anchor in a global coordinate frame -->
+ <limit effort="100" velocity="5" />
<calibration values="1.5 -1 " /> <!-- Calibration stop/flag indicating location and then direction -->
</const_block>
@@ -943,13 +945,12 @@
<include>groups_arm_test.xml</include>
+ <!-- new definitions for mechanism controls - JMH -->
+ <include>controllers_arm_test.xml</include>
+ <include>actuators_arm_test.xml</include>
+ <include>transmissions_arm_test.xml</include>
+
<!-- controllers for gazebo -->
<include>controllers_gazebo_arm_test_headless.xml</include>
- <!-- new definitions for mechanism controls - JMH -->
- <!--
- <include>controllers.xml</include>
- <include>actuators.xml</include>
- <include>transmissions.xml</include>
- -->
</robot>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm_test.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test/transmissions_arm_test.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -56,10 +56,13 @@
</transmission>
<!-- fingers share a single motor -->
- <transmission type="SimpleTransmission" name="gripper_left_trans">
+ <transmission type="GripperTransmission" name="gripper_left_trans">
<actuator name="gripper_left_motor" />
- <joint name="gripper_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
+ <joint name="finger_r_left_joint" reduction="-1.0" />
+ <joint name="finger_tip_r_left_joint" reduction="1.0" />
+ <joint name="finger_l_left_joint" reduction="1.0" />
+ <joint name="finger_tip_l_left_joint" reduction="-1.0" />
+ <pid p="0.10" i="0.0" d="0.005" iClamp="0.5" />
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_headless.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_headless.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -17,7 +17,6 @@
<robot_filename>pr2_arm_test_tjh.xml</robot_filename>
<controller_filename>controllers_arm_test_tjh.xml</controller_filename>
<actuator_filename>actuators_arm_test.xml</actuator_filename>
- <transmission_filename>transmissions_arm_test.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_tjh.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_tjh.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/controllers_gazebo_arm_test_tjh.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -17,7 +17,6 @@
<robot_filename>pr2_arm_test_tjh.xml</robot_filename>
<controller_filename>controllers_arm_test_tjh.xml</controller_filename>
<actuator_filename>actuators_arm_test.xml</actuator_filename>
- <transmission_filename>transmissions_arm_test.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/transmissions_arm_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/transmissions_arm_test.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2_arm_test_tjh/transmissions_arm_test.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -56,10 +56,13 @@
</transmission>
<!-- fingers share a single motor -->
- <transmission type="SimpleTransmission" name="gripper_left_trans">
+ <transmission type="GripperTransmission" name="gripper_left_trans">
<actuator name="gripper_left_motor" />
- <joint name="gripper_left_joint" />
- <mechanicalReduction>1</mechanicalReduction>
+ <joint name="finger_r_left_joint" reduction="-1.0" />
+ <joint name="finger_tip_r_left_joint" reduction="1.0" />
+ <joint name="finger_l_left_joint" reduction="1.0" />
+ <joint name="finger_tip_l_left_joint" reduction="-1.0" />
+ <pid p="0.10" i="0.0" d="0.005" iClamp="0.5" />
<motorTorqueConstant>1</motorTorqueConstant>
<pulsesPerRevolution>90000</pulsesPerRevolution>
</transmission>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_gazebo_single_link.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_gazebo_single_link.xml 2008-09-09 02:32:59 UTC (rev 4075)
+++ pkg/trunk/robot_descriptions/wg_robot_description/single_link_test/controllers_gazebo_single_link.xml 2008-09-09 02:49:31 UTC (rev 4076)
@@ -17,7 +17,6 @@
<robot_filename>pr2_single_link.xml</robot_filename>
<controller_filename>controllers_single_link.xml</controller_filename>
<actuator_filename>actuators_single_link.xml</actuator_filename>
- <transmission_filename>transmissions_single_link.xml</transmission_filename>
<interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <jfa...@us...> - 2008-09-09 17:50:28
|
Revision: 4095
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4095&view=rev
Author: jfaustwg
Date: 2008-09-09 17:50:37 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
Deprecating pr2_gui
Added Paths:
-----------
pkg/trunk/deprecated/pr2_gui/
Removed Paths:
-------------
pkg/trunk/visualization/pr2_gui/
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <is...@us...> - 2008-09-09 17:50:54
|
Revision: 4096
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4096&view=rev
Author: isucan
Date: 2008-09-09 17:51:02 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
first version of a motion_validator
Modified Paths:
--------------
pkg/trunk/motion_planning/kinematic_planning/CMakeLists.txt
pkg/trunk/motion_planning/kinematic_planning/include/RKPBasicRequest.h
pkg/trunk/motion_planning/kinematic_planning/include/RKPPlannerSetup.h
pkg/trunk/robot_srvs/srv/KinematicPlanState.srv
Added Paths:
-----------
pkg/trunk/motion_planning/kinematic_planning/include/RKPSpaceInformation.h
pkg/trunk/motion_planning/kinematic_planning/include/RKPStateValidator.h
pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
pkg/trunk/robot_srvs/srv/ValidateKinematicPath.srv
Modified: pkg/trunk/motion_planning/kinematic_planning/CMakeLists.txt
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/CMakeLists.txt 2008-09-09 17:50:37 UTC (rev 4095)
+++ pkg/trunk/motion_planning/kinematic_planning/CMakeLists.txt 2008-09-09 17:51:02 UTC (rev 4096)
@@ -2,5 +2,8 @@
include(rosbuild)
rospack(kinematic_planning)
rospack_add_executable(kinematic_planning src/kinematic_planning.cpp)
+rospack_add_executable(motion_validator src/motion_validator.cpp)
+rospack_add_link_flags(kinematic_planning)
+rospack_add_link_flags(motion_validator)
+
add_subdirectory(test)
-rospack_add_link_flags(kinematic_planning)
Modified: pkg/trunk/motion_planning/kinematic_planning/include/RKPBasicRequest.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/RKPBasicRequest.h 2008-09-09 17:50:37 UTC (rev 4095)
+++ pkg/trunk/motion_planning/kinematic_planning/include/RKPBasicRequest.h 2008-09-09 17:51:02 UTC (rev 4096)
@@ -118,10 +118,10 @@
/* set the workspace volume for planning */
// only area or volume should go through... not sure what happens on really complicated models where
// we have both multiple planar and multiple floating joints...
- static_cast<RKPPlannerSetup::SpaceInformationRKPModel*>(psetup->si)->setPlanningArea(params.volumeMin.x, params.volumeMin.y,
- params.volumeMax.x, params.volumeMax.y);
- static_cast<RKPPlannerSetup::SpaceInformationRKPModel*>(psetup->si)->setPlanningVolume(params.volumeMin.x, params.volumeMin.y, params.volumeMin.z,
- params.volumeMax.x, params.volumeMax.y, params.volumeMax.z);
+ static_cast<SpaceInformationRKPModel*>(psetup->si)->setPlanningArea(params.volumeMin.x, params.volumeMin.y,
+ params.volumeMax.x, params.volumeMax.y);
+ static_cast<SpaceInformationRKPModel*>(psetup->si)->setPlanningVolume(params.volumeMin.x, params.volumeMin.y, params.volumeMin.z,
+ params.volumeMax.x, params.volumeMax.y, params.volumeMax.z);
psetup->si->setStateDistanceEvaluator(psetup->sde[params.distance_metric]);
@@ -152,7 +152,7 @@
/** Set the kinematic constraints to follow */
void setupPoseConstraints(RKPPlannerSetup *psetup, const std::vector<robot_msgs::PoseConstraint> &cstrs)
{
- static_cast<RKPPlannerSetup::StateValidityPredicate*>(psetup->si->getStateValidityChecker())->setPoseConstraints(cstrs);
+ static_cast<StateValidityPredicate*>(psetup->si->getStateValidityChecker())->setPoseConstraints(cstrs);
}
/** Compute the actual motion plan */
Modified: pkg/trunk/motion_planning/kinematic_planning/include/RKPPlannerSetup.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/RKPPlannerSetup.h 2008-09-09 17:50:37 UTC (rev 4095)
+++ pkg/trunk/motion_planning/kinematic_planning/include/RKPPlannerSetup.h 2008-09-09 17:51:02 UTC (rev 4096)
@@ -37,23 +37,20 @@
#ifndef KINEMATIC_PLANNING_RKP_PLANNER_SETUP_
#define KINEMATIC_PLANNING_RKP_PLANNER_SETUP_
+#include "RKPModelBase.h"
+#include "RKPStateValidator.h"
+#include "RKPSpaceInformation.h"
+
#include <ompl/base/Planner.h>
-#include <ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h>
#include <ompl/extension/samplingbased/kinematic/PathSmootherKinematic.h>
-#include <planning_models/kinematic.h>
#include <string_utils/string_utils.h>
-
#include <cassert>
-#include <iostream>
#include <vector>
#include <string>
#include <map>
-#include "RKPModelBase.h"
-#include "RKPConstraintEvaluator.h"
-
class RKPPlannerSetup
{
public:
@@ -81,153 +78,6 @@
delete si;
}
- /** This class configures an instance of SpaceInformationKinematic with data from a KinematicModel */
- class SpaceInformationRKPModel : public ompl::SpaceInformationKinematic
- {
- public:
- SpaceInformationRKPModel(RKPModelBase *model, double divisions = 20.0) : SpaceInformationKinematic()
- {
- m_kmodel = model->kmodel;
- m_groupID = model->groupID;
- m_divisions = divisions;
-
- /* compute the state space for this group */
- m_stateDimension = m_groupID >= 0 ? m_kmodel->groupStateIndexList[m_groupID].size() : m_kmodel->stateDimension;
- m_stateComponent.resize(m_stateDimension);
-
- for (unsigned int i = 0 ; i < m_stateDimension ; ++i)
- {
- if (m_stateComponent[i].type == StateComponent::UNKNOWN)
- m_stateComponent[i].type = StateComponent::NORMAL;
- int p = m_groupID >= 0 ? m_kmodel->groupStateIndexList[m_groupID][i] * 2 : i * 2;
- m_stateComponent[i].minValue = m_kmodel->stateBounds[p ];
- m_stateComponent[i].maxValue = m_kmodel->stateBounds[p + 1];
- m_stateComponent[i].resolution = (m_stateComponent[i].maxValue - m_stateComponent[i].minValue) / m_divisions;
-
- for (unsigned int j = 0 ; j < m_kmodel->floatingJoints.size() ; ++j)
- if (m_kmodel->floatingJoints[j] == p)
- {
- m_floatingJoints.push_back(i);
- m_stateComponent[i + 3].type = StateComponent::QUATERNION;
- break;
- }
-
- for (unsigned int j = 0 ; j < m_kmodel->planarJoints.size() ; ++j)
- if (m_kmodel->planarJoints[j] == p)
- {
- m_planarJoints.push_back(i);
- break;
- }
- }
- updateResolution();
- }
-
- virtual ~SpaceInformationRKPModel(void)
- {
- }
-
- /** For planar and floating joints, we have infinite
- dimensions. The bounds for these dimensions are set by the
- user. */
- void setPlanningVolume(double x0, double y0, double z0, double x1, double y1, double z1)
- {
- for (unsigned int i = 0 ; i < m_floatingJoints.size() ; ++i)
- {
- int id = m_floatingJoints[i];
- m_stateComponent[id ].minValue = x0;
- m_stateComponent[id ].maxValue = x1;
- m_stateComponent[id + 1].minValue = y0;
- m_stateComponent[id + 1].maxValue = y1;
- m_stateComponent[id + 2].minValue = z0;
- m_stateComponent[id + 2].maxValue = z1;
- for (int j = 0 ; j < 3 ; ++j)
- m_stateComponent[j + id].resolution = (m_stateComponent[j + id].maxValue - m_stateComponent[j + id].minValue) / m_divisions;
- }
- updateResolution();
- }
-
- void setPlanningArea(double x0, double y0, double x1, double y1)
- {
- for (unsigned int i = 0 ; i < m_planarJoints.size() ; ++i)
- {
- int id = m_planarJoints[i];
- m_stateComponent[id ].minValue = x0;
- m_stateComponent[id ].maxValue = x1;
- m_stateComponent[id + 1].minValue = y0;
- m_stateComponent[id + 1].maxValue = y1;
- for (int j = 0 ; j < 2 ; ++j)
- m_stateComponent[j + id].resolution = (m_stateComponent[j + id].maxValue - m_stateComponent[j + id].minValue) / m_divisions;
- }
- updateResolution();
- }
-
- protected:
-
- void updateResolution(void)
- {
- /* for movement in plane/space, we want to make sure the resolution is small enough */
- for (unsigned int i = 0 ; i < m_planarJoints.size() ; ++i)
- {
- if (m_stateComponent[m_planarJoints[i]].resolution > 0.1)
- m_stateComponent[m_planarJoints[i]].resolution = 0.1;
- if (m_stateComponent[m_planarJoints[i] + 1].resolution > 0.1)
- m_stateComponent[m_planarJoints[i] + 1].resolution = 0.1;
- }
- for (unsigned int i = 0 ; i < m_floatingJoints.size() ; ++i)
- {
- if (m_stateComponent[m_floatingJoints[i]].resolution > 0.1)
- m_stateComponent[m_floatingJoints[i]].resolution = 0.1;
- if (m_stateComponent[m_floatingJoints[i] + 1].resolution > 0.1)
- m_stateComponent[m_floatingJoints[i] + 1].resolution = 0.1;
- if (m_stateComponent[m_floatingJoints[i] + 2].resolution > 0.1)
- m_stateComponent[m_floatingJoints[i] + 2].resolution = 0.1;
- }
- }
-
- double m_divisions;
- planning_models::KinematicModel *m_kmodel;
- int m_groupID;
- std::vector<int> m_floatingJoints;
- std::vector<int> m_planarJoints;
-
- };
-
- class StateValidityPredicate : public ompl::SpaceInformation::StateValidityChecker
- {
- public:
- StateValidityPredicate(RKPModelBase *model) : ompl::SpaceInformation::StateValidityChecker()
- {
- m_model = model;
- }
-
- virtual bool operator()(const ompl::SpaceInformation::State_t state)
- {
- m_model->kmodel->computeTransforms(static_cast<const ompl::SpaceInformationKinematic::StateKinematic_t>(state)->values, m_model->groupID);
- m_model->collisionSpace->updateRobotModel(m_model->collisionSpaceID);
-
- bool valid = !m_model->collisionSpace->isCollision(m_model->collisionSpaceID);
-
- if (valid)
- valid = m_kce.decide();
-
- return valid;
- }
-
- void setPoseConstraints(const std::vector<robot_msgs::PoseConstraint> &kc)
- {
- m_kce.use(m_model->kmodel, kc);
- }
-
- void clearConstraints(void)
- {
- m_kce.clear();
- }
-
- protected:
- RKPModelBase *m_model;
- KinematicConstraintEvaluatorSet m_kce;
- };
-
/* for each planner definition, define the set of distance metrics it can use */
virtual void setupDistanceEvaluators(void)
{
Added: pkg/trunk/motion_planning/kinematic_planning/include/RKPSpaceInformation.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/RKPSpaceInformation.h (rev 0)
+++ pkg/trunk/motion_planning/kinematic_planning/include/RKPSpaceInformation.h 2008-09-09 17:51:02 UTC (rev 4096)
@@ -0,0 +1,156 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* 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.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may 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 Ioan Sucan */
+
+#ifndef KINEMATIC_PLANNING_RKP_SPACE_INFORMATION_
+#define KINEMATIC_PLANNING_RKP_SPACE_INFORMATION_
+
+#include <ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h>
+#include "RKPModelBase.h"
+
+#include <vector>
+
+/** This class configures an instance of SpaceInformationKinematic with data from a KinematicModel */
+class SpaceInformationRKPModel : public ompl::SpaceInformationKinematic
+{
+ public:
+ SpaceInformationRKPModel(RKPModelBase *model, double divisions = 20.0) : SpaceInformationKinematic()
+ {
+ m_kmodel = model->kmodel;
+ m_groupID = model->groupID;
+ m_divisions = divisions;
+
+ /* compute the state space for this group */
+ m_stateDimension = m_groupID >= 0 ? m_kmodel->groupStateIndexList[m_groupID].size() : m_kmodel->stateDimension;
+ m_stateComponent.resize(m_stateDimension);
+
+ for (unsigned int i = 0 ; i < m_stateDimension ; ++i)
+ {
+ if (m_stateComponent[i].type == StateComponent::UNKNOWN)
+ m_stateComponent[i].type = StateComponent::NORMAL;
+ int p = m_groupID >= 0 ? m_kmodel->groupStateIndexList[m_groupID][i] * 2 : i * 2;
+ m_stateComponent[i].minValue = m_kmodel->stateBounds[p ];
+ m_stateComponent[i].maxValue = m_kmodel->stateBounds[p + 1];
+ m_stateComponent[i].resolution = (m_stateComponent[i].maxValue - m_stateComponent[i].minValue) / m_divisions;
+
+ for (unsigned int j = 0 ; j < m_kmodel->floatingJoints.size() ; ++j)
+ if (m_kmodel->floatingJoints[j] == p)
+ {
+ m_floatingJoints.push_back(i);
+ m_stateComponent[i + 3].type = StateComponent::QUATERNION;
+ break;
+ }
+
+ for (unsigned int j = 0 ; j < m_kmodel->planarJoints.size() ; ++j)
+ if (m_kmodel->planarJoints[j] == p)
+ {
+ m_planarJoints.push_back(i);
+ break;
+ }
+ }
+ updateResolution();
+ }
+
+ virtual ~SpaceInformationRKPModel(void)
+ {
+ }
+
+ /** For planar and floating joints, we have infinite
+ dimensions. The bounds for these dimensions are set by the
+ user. */
+ void setPlanningVolume(double x0, double y0, double z0, double x1, double y1, double z1)
+ {
+ for (unsigned int i = 0 ; i < m_floatingJoints.size() ; ++i)
+ {
+ int id = m_floatingJoints[i];
+ m_stateComponent[id ].minValue = x0;
+ m_stateComponent[id ].maxValue = x1;
+ m_stateComponent[id + 1].minValue = y0;
+ m_stateComponent[id + 1].maxValue = y1;
+ m_stateComponent[id + 2].minValue = z0;
+ m_stateComponent[id + 2].maxValue = z1;
+ for (int j = 0 ; j < 3 ; ++j)
+ m_stateComponent[j + id].resolution = (m_stateComponent[j + id].maxValue - m_stateComponent[j + id].minValue) / m_divisions;
+ }
+ updateResolution();
+ }
+
+ void setPlanningArea(double x0, double y0, double x1, double y1)
+ {
+ for (unsigned int i = 0 ; i < m_planarJoints.size() ; ++i)
+ {
+ int id = m_planarJoints[i];
+ m_stateComponent[id ].minValue = x0;
+ m_stateComponent[id ].maxValue = x1;
+ m_stateComponent[id + 1].minValue = y0;
+ m_stateComponent[id + 1].maxValue = y1;
+ for (int j = 0 ; j < 2 ; ++j)
+ m_stateComponent[j + id].resolution = (m_stateComponent[j + id].maxValue - m_stateComponent[j + id].minValue) / m_divisions;
+ }
+ updateResolution();
+ }
+
+ protected:
+
+ void updateResolution(void)
+ {
+ /* for movement in plane/space, we want to make sure the resolution is small enough */
+ for (unsigned int i = 0 ; i < m_planarJoints.size() ; ++i)
+ {
+ if (m_stateComponent[m_planarJoints[i]].resolution > 0.1)
+ m_stateComponent[m_planarJoints[i]].resolution = 0.1;
+ if (m_stateComponent[m_planarJoints[i] + 1].resolution > 0.1)
+ m_stateComponent[m_planarJoints[i] + 1].resolution = 0.1;
+ }
+ for (unsigned int i = 0 ; i < m_floatingJoints.size() ; ++i)
+ {
+ if (m_stateComponent[m_floatingJoints[i]].resolution > 0.1)
+ m_stateComponent[m_floatingJoints[i]].resolution = 0.1;
+ if (m_stateComponent[m_floatingJoints[i] + 1].resolution > 0.1)
+ m_stateComponent[m_floatingJoints[i] + 1].resolution = 0.1;
+ if (m_stateComponent[m_floatingJoints[i] + 2].resolution > 0.1)
+ m_stateComponent[m_floatingJoints[i] + 2].resolution = 0.1;
+ }
+ }
+
+ double m_divisions;
+ planning_models::KinematicModel *m_kmodel;
+ int m_groupID;
+ std::vector<int> m_floatingJoints;
+ std::vector<int> m_planarJoints;
+
+};
+
+#endif
Added: pkg/trunk/motion_planning/kinematic_planning/include/RKPStateValidator.h
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/include/RKPStateValidator.h (rev 0)
+++ pkg/trunk/motion_planning/kinematic_planning/include/RKPStateValidator.h 2008-09-09 17:51:02 UTC (rev 4096)
@@ -0,0 +1,82 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* 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.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may 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 Ioan Sucan */
+
+#ifndef KINEMATIC_PLANNING_RKP_STATE_VALIDATOR
+#define KINEMATIC_PLANNING_RKP_STATE_VALIDATOR
+
+#include <ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h>
+#include <planning_models/kinematic.h>
+#include <collision_space/environment.h>
+#include "RKPModelBase.h"
+#include "RKPConstraintEvaluator.h"
+
+class StateValidityPredicate : public ompl::SpaceInformation::StateValidityChecker
+{
+ public:
+ StateValidityPredicate(RKPModelBase *model) : ompl::SpaceInformation::StateValidityChecker()
+ {
+ m_model = model;
+ }
+
+ virtual bool operator()(const ompl::SpaceInformation::State_t state)
+ {
+ m_model->kmodel->computeTransforms(static_cast<const ompl::SpaceInformationKinematic::StateKinematic_t>(state)->values, m_model->groupID);
+ m_model->collisionSpace->updateRobotModel(m_model->collisionSpaceID);
+
+ bool valid = !m_model->collisionSpace->isCollision(m_model->collisionSpaceID);
+
+ if (valid)
+ valid = m_kce.decide();
+
+ return valid;
+ }
+
+ void setPoseConstraints(const std::vector<robot_msgs::PoseConstraint> &kc)
+ {
+ m_kce.use(m_model->kmodel, kc);
+ }
+
+ void clearConstraints(void)
+ {
+ m_kce.clear();
+ }
+
+ protected:
+ RKPModelBase *m_model;
+ KinematicConstraintEvaluatorSet m_kce;
+};
+
+#endif
Added: pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp (rev 0)
+++ pkg/trunk/motion_planning/kinematic_planning/src/motion_validator.cpp 2008-09-09 17:51:02 UTC (rev 4096)
@@ -0,0 +1,292 @@
+/*********************************************************************
+* Software License Agreement (BSD License)
+*
+* Copyright (c) 2008, Willow Garage, Inc.
+* All rights reserved.
+*
+* 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.
+* * Neither the name of the Willow Garage nor the names of its
+* contributors may 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 Ioan Sucan */
+
+/**
+
+@mainpage
+
+@htmlinclude ../manifest.html
+
+@b MotionValidator is a node capable of verifying if a path is valid
+or not (collides or does not collide).
+
+<hr>
+
+@section usage Usage
+@verbatim
+$ motion_validator robot_model [standard ROS args]
+@endverbatim
+
+@par Example
+
+@verbatim
+$ motion_validator robotdesc/pr2
+@endverbatim
+
+<hr>
+
+@section topic ROS topics
+
+Subscribes to (name/type):
+- None
+
+Additional subscriptions due to inheritance from NodeCollisionModel:
+- @b localizedpose/RobotBase2DOdom : localized position of the robot base
+- @b world_3d_map/PointCloudFloat32 : point cloud with data describing the 3D environment
+
+Publishes to (name/type):
+- None
+
+<hr>
+
+@section services ROS services
+
+Uses (name/type):
+- None
+
+Provides (name/type):
+- @b "validate_path"/KinematicPlanState : given a robot model, starting and goal states, this service computes a collision free path
+
+
+<hr>
+
+@section parameters ROS parameters
+- None
+
+**/
+
+#include <planning_node_util/cnode.h>
+#include <ompl/extension/samplingbased/kinematic/SpaceInformationKinematic.h>
+
+#include <robot_srvs/ValidateKinematicPath.h>
+
+#include "RKPStateValidator.h"
+#include "RKPSpaceInformation.h"
+
+#include <iostream>
+#include <string>
+#include <map>
+
+class MotionValidator : public ros::node,
+ public planning_node_util::NodeCollisionModel
+{
+public:
+
+ class myModel : public RKPModelBase
+ {
+ public:
+ myModel(void) : RKPModelBase()
+ {
+ si = NULL;
+ svc = NULL;
+ }
+
+ virtual ~myModel(void)
+ {
+ if (svc)
+ delete svc;
+ if (si)
+ delete si;
+ }
+
+ ompl::SpaceInformationKinematic_t si;
+ ompl::SpaceInformation::StateValidityChecker_t svc;
+ };
+
+ MotionValidator(const std::string &robot_model) : ros::node("kinematic_planning"),
+ planning_node_util::NodeCollisionModel(dynamic_cast<ros::node*>(this),
+ robot_model)
+ {
+ advertise_service("validate_path", &MotionValidator::validatePath);
+ }
+
+ /** Free the memory */
+ virtual ~MotionValidator(void)
+ {
+ for (std::map<std::string, myModel*>::iterator i = m_models.begin() ; i != m_models.end() ; i++)
+ delete i->second;
+ }
+
+ bool validatePath(robot_srvs::ValidateKinematicPath::request &req, robot_srvs::ValidateKinematicPath::response &res)
+ {
+ myModel *model = m_models[req.model_id];
+ if (model)
+ {
+ if (model->kmodel->stateDimension != req.start_state.get_vals_size())
+ {
+ std::cerr << "Dimension of start state expected to be " << model->kmodel->stateDimension << " but was received as " << req.start_state.get_vals_size() << std::endl;
+ return false;
+ }
+
+ if (model->si->getStateDimension() != req.goal_state.get_vals_size())
+ {
+ std::cerr << "Dimension of start goal expected to be " << model->si->getStateDimension() << " but was received as " << req.goal_state.get_vals_size() << std::endl;
+ return false;
+ }
+
+ std::cout << "Validating path for '" << req.model_id << "'..." << std::endl;
+
+ const unsigned int dim = model->si->getStateDimension();
+ ompl::SpaceInformationKinematic::StateKinematic_t start = new ompl::SpaceInformationKinematic::StateKinematic(dim);
+
+ if (model->groupID >= 0)
+ {
+ /* set the pose of the whole robot */
+ model->kmodel->computeTransforms(req.start_state.vals);
+ model->collisionSpace->updateRobotModel(model->collisionSpaceID);
+
+ /* extract the components needed for the start state of the desired group */
+ for (unsigned int i = 0 ; i < dim ; ++i)
+ start->values[i] = req.start_state.vals[model->kmodel->groupStateIndexList[model->groupID][i]];
+ }
+ else
+ {
+ /* the start state is the complete state */
+ for (unsigned int i = 0 ; i < dim ; ++i)
+ start->values[i] = req.start_state.vals[i];
+ }
+
+ ompl::SpaceInformationKinematic::StateKinematic_t goal = new ompl::SpaceInformationKinematic::StateKinematic(dim);
+ for (unsigned int i = 0 ; i < dim ; ++i)
+ goal->values[i] = req.goal_state.vals[i];
+
+
+ res.valid = model->si->checkMotionIncremental(start, goal);
+
+ std::cout << "Result: " << res.valid << std::endl;
+
+ delete start;
+ delete goal;
+
+ return true;
+ }
+ else
+ {
+ std::cerr << "Model '" << req.model_id << "' not known" << std::endl;
+ return false;
+ }
+ }
+
+ virtual void setRobotDescription(robot_desc::URDF *file)
+ {
+ planning_node_util::NodeCollisionModel::setRobotDescription(file);
+
+ printf("=======================================\n");
+ m_kmodel->printModelInfo();
+ printf("=======================================\n");
+
+ /* set the data for the model */
+ myModel *model = new myModel();
+ model->collisionSpaceID = 0;
+ model->collisionSpace = m_collisionSpace;
+ model->kmodel = m_kmodel;
+ model->groupName = m_kmodel->name;
+ setupModel(model);
+
+ /* remember the model by the robot's name */
+ m_models[model->groupName] = model;
+
+ /* create a model for each group */
+ std::vector<std::string> groups;
+ m_kmodel->getGroups(groups);
+
+ for (unsigned int i = 0 ; i < groups.size() ; ++i)
+ {
+ myModel *model = new myModel();
+ model->collisionSpaceID = 0;
+ model->collisionSpace = m_collisionSpace;
+ model->kmodel = m_kmodel;
+ model->groupID = m_kmodel->getGroupID(groups[i]);
+ model->groupName = groups[i];
+ setupModel(model);
+ m_models[model->groupName] = model;
+ }
+ }
+
+ void knownModels(std::vector<std::string> &model_ids)
+ {
+ for (std::map<std::string, myModel*>::const_iterator i = m_models.begin() ; i != m_models.end() ; ++i)
+ model_ids.push_back(i->first);
+ }
+
+private:
+
+ void setupModel(myModel *model)
+ {
+ model->si = new SpaceInformationRKPModel(model);
+ model->svc = new StateValidityPredicate(model);
+ model->si->setStateValidityChecker(model->svc);
+ }
+
+ std::map<std::string, myModel*> m_models;
+
+
+};
+
+void usage(const char *progname)
+{
+ printf("\nUsage: %s robot_model [standard ROS args]\n", progname);
+ printf(" \"robot_model\" is the name (string) of a robot description to be used for path validation.\n");
+}
+
+int main(int argc, char **argv)
+{
+ if (argc == 2)
+ {
+ ros::init(argc, argv);
+
+ MotionValidator *validator = new MotionValidator(argv[1]);
+ validator->loadRobotDescription();
+
+ std::vector<std::string> mlist;
+ validator->knownModels(mlist);
+ printf("Known models:\n");
+ for (unsigned int i = 0 ; i < mlist.size() ; ++i)
+ printf(" * %s\n", mlist[i].c_str());
+ if (mlist.size() > 0)
+ validator->spin();
+ else
+ printf("No models defined. Path validation node cannot start.\n");
+
+ validator->shutdown();
+
+ delete validator;
+ }
+ else
+ usage(argv[0]);
+
+ return 0;
+}
Modified: pkg/trunk/robot_srvs/srv/KinematicPlanState.srv
===================================================================
--- pkg/trunk/robot_srvs/srv/KinematicPlanState.srv 2008-09-09 17:50:37 UTC (rev 4095)
+++ pkg/trunk/robot_srvs/srv/KinematicPlanState.srv 2008-09-09 17:51:02 UTC (rev 4096)
@@ -15,9 +15,7 @@
# The goal state for the model to plan for. The dimension of this
# state must be equal to the dimension of the state space
-# characterizing the model (group) to plan for. If this state has
-# dimension 0, it is assumed that the first state that satisfies the
-# constraints is correct
+# characterizing the model (group) to plan for.
robot_msgs/KinematicState goal_state
# No state in the produced motion plan will violate these constraints
Added: pkg/trunk/robot_srvs/srv/ValidateKinematicPath.srv
...
[truncated message content] |
|
From: <hsu...@us...> - 2008-09-09 21:26:51
|
Revision: 4114
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4114&view=rev
Author: hsujohnhsu
Date: 2008-09-09 21:27:00 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
removed dependence on libpr2HW, libpr2API, rosgazebo pr2_gazebo.
move pr2Core into deprecated, awaiting updates to:
pr2_etherDrive - this currently runs on the hardware, we need to remove dependency on pr2Core, though this will be replaced by pr2_etherCAT eventually.
exec_trex, executive_trex_pr2
libKinematics - will be deprecated itself soon
overhead_grasp_behavior
pr2_kinematic_controllers
and following deprecated packages are now broken, but should have no impact on working code.
genericControllers
rosControllers
testControllers
pr2Controllers
old_mechanism_control
pr2_gui
libKDL
Modified Paths:
--------------
pkg/trunk/clean_rosgazebo.scp
pkg/trunk/demos/2dnav-gazebo/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world
pkg/trunk/simulators/simulator_integration_tests/manifest.xml
Added Paths:
-----------
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_nolimit.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_wg.world
Removed Paths:
-------------
pkg/trunk/drivers/robot/pr2/libpr2API/
pkg/trunk/drivers/robot/pr2/libpr2HW/
pkg/trunk/drivers/robot/pr2/pr2Core/
pkg/trunk/drivers/simulator/gazebo_hardware/
pkg/trunk/drivers/simulator/gazebo_sensors/
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo_wg.world
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_rosgazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2_rosgazebo.xml
pkg/trunk/simulators/rosgazebo/include/
pkg/trunk/simulators/rosgazebo/manifest.xml
pkg/trunk/simulators/rosgazebo/run-rosgazebo.sh
pkg/trunk/simulators/rosgazebo/setup.bash
pkg/trunk/simulators/rosgazebo/setup.tcsh
pkg/trunk/simulators/rosgazebo/src/
pkg/trunk/simulators/rosgazebo/srv/
Modified: pkg/trunk/clean_rosgazebo.scp
===================================================================
--- pkg/trunk/clean_rosgazebo.scp 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/clean_rosgazebo.scp 2008-09-09 21:27:00 UTC (rev 4114)
@@ -2,20 +2,11 @@
#clean controllers
(cd `rospack find generic_controllers` ; rm -f lib/* ;make clean)
-(cd `rospack find genericControllers` ; rm -f lib/* ;make clean)
-(cd `rospack find pr2Controllers` ; rm -f lib/* ;make clean)
+(cd `rospack find pr2_controllers` ; rm -f lib/* ;make clean)
-#clean gazebo dependent stuff
-(cd `rospack find libpr2HW` ; rm -f lib/* ;make clean)
-(cd `rospack find libpr2API` ; rm -f lib/* ;make clean)
-
+# clean gazebo plugins
(cd `rospack find gazebo_plugin` ; rm -f lib/* ;make clean)
-(cd `rospack find gazebo_hardware` ; rm -f lib/* ;make clean)
-(cd `rospack find gazebo_sensors` ; rm -f lib/* ;make clean)
-(cd `rospack find rosgazebo` ; rm -f lib/* ;make clean)
-(cd `rospack find pr2_gazebo` ; rm -f lib/* ;make clean)
-
#clean 2dnav stack stuff
(cd `rospack find nav_view` ; rm -f lib/* ;make clean)
(cd `rospack find amcl_player` ; rm -f lib/* ;make clean)
@@ -28,13 +19,17 @@
# clean kinematics
(cd `rospack find libKinematics` ; rm -f lib/* ;make clean)
-(cd `rospack find libKDL` ; rm -f lib/* ;make clean)
(cd `rospack find robot_kinematics` ; rm -f lib/* ;make clean)
# clean visualization
(cd `rospack find irrlicht_viewer` ; rm -f lib/* ;make clean)
(cd `rospack find cloud_viewer` ; rm -f lib/* ;make clean)
+(cd `rospack find ogre_visualizer` ; rm -f lib/* ;make clean)
+# clean mechanism control
+(cd `rospack find mechanism_control` ; rm -f lib/* ;make clean)
+(cd `rospack find mechanism_model` ; rm -f lib/* ;make clean)
+
# note for users
echo "if gazebo still functions incorrectly, please perform a make wipe in 3rdparty/gazebo directory."
echo "now, to rebuild everything again, do rosmake 2dnav-gazebo, or some subset of stuff."
Modified: pkg/trunk/demos/2dnav-gazebo/manifest.xml
===================================================================
--- pkg/trunk/demos/2dnav-gazebo/manifest.xml 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/demos/2dnav-gazebo/manifest.xml 2008-09-09 21:27:00 UTC (rev 4114)
@@ -9,7 +9,6 @@
<depend package="map_server"/>
<depend package="amcl_player"/>
<depend package="fake_localization"/>
- <depend package="pr2_gazebo"/>
<depend package="wavefront_player"/>
<depend package="teleop_base_keyboard"/>
<depend package="teleop_arm_keyboard"/>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/CMakeLists.txt 2008-09-09 21:27:00 UTC (rev 4114)
@@ -7,11 +7,11 @@
include_directories(srv/cpp)
add_definitions(-Wall)
-rospack_add_library(Pr2_Actarray src/Pr2_Actarray.cc)
-rospack_add_library(Pr2_Gripper src/Pr2_Gripper.cc)
+#rospack_add_library(Pr2_Actarray src/Pr2_Actarray.cc)
+#rospack_add_library(Pr2_Gripper src/Pr2_Gripper.cc)
rospack_add_library(Ros_Camera src/Ros_Camera.cc)
rospack_add_library(Ros_Laser src/Ros_Laser.cc)
-rospack_add_library(Ros_Node src/Ros_Node.cc)
+#rospack_add_library(Ros_Node src/Ros_Node.cc)
rospack_add_library(Ros_PTZ src/Ros_PTZ.cc)
rospack_add_library(P3D src/P3D.cc)
rospack_add_library(gazebo_actuators src/gazebo_actuators.cpp)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/P3D.hh 2008-09-09 21:27:00 UTC (rev 4114)
@@ -29,7 +29,6 @@
#include <gazebo/Controller.hh>
#include <gazebo/Entity.hh>
-#include <pr2Core/pr2Core.h>
#include <ros/node.h>
#include <std_msgs/Pose3DStamped.h>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2008-09-09 21:27:00 UTC (rev 4114)
@@ -10,7 +10,6 @@
<url>http://pr.willowgarage.com</url>
<depend package="gazebo"/>
<depend package="opende"/>
-<depend package="pr2Core"/>
<depend package="newmat10"/>
<depend package="generic_controllers"/>
<depend package="pr2_controllers"/>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/CMakeLists.txt 2008-09-09 21:27:00 UTC (rev 4114)
@@ -18,21 +18,16 @@
DEPENDS urdf2gazebo
COMMENT "Building Gazebo model for PR2 Standard Model")
-add_custom_target(pr2_gazebo_model_nolimit_rosgazebo ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_rosgazebo.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_nolimit.model 1
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2 Rosgazebo Model without Joint Limits for Kinematics")
-
-add_custom_target(pr2_gazebo_model_rosgazebo ALL
- COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_rosgazebo.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_rosgazebo.model
- DEPENDS urdf2gazebo
- COMMENT "Building Gazebo model for PR2 Rosgazebo Model")
-
add_custom_target(pr2_gazebo_model_test ALL
COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_test_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_test.model
DEPENDS urdf2gazebo
COMMENT "Building Gazebo model for PR2 Test Actuators")
+add_custom_target(pr2_gazebo_model_nolimit_test ALL
+ COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2/pr2_test_actuators.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_nolimit_test.model 1
+ DEPENDS urdf2gazebo
+ COMMENT "Building Gazebo model for PR2 Test Actuators with no limits")
+
add_custom_target(pr2_gazebo_model_arm_test ALL
COMMAND ${urdf2gazebo_exe} ${wg_robot_description_PACKAGE_PATH}/pr2_arm_test/pr2_arm_test.xml ${gazebo_robot_description_PACKAGE_PATH}/world/pr2_xml_arm_test.model
DEPENDS urdf2gazebo
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world 2008-09-09 21:27:00 UTC (rev 4114)
@@ -346,7 +346,7 @@
<!-- base, torso and arms -->
<include embedded="true">
- <xi:include href="pr2_xml_rosgazebo.model" />
+ <xi:include href="pr2_xml_test.model" />
</include>
</model:physical>
Deleted: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo.world 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo.world 2008-09-09 21:27:00 UTC (rev 4114)
@@ -1,331 +0,0 @@
-<?xml version="1.0"?>
-
-<gazebo:world
- xmlns:xi="http://www.w3.org/2001/XInclude"
- xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
- xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
- xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window"
- xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param"
- xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
- xmlns:geo="http://willowgarage.com/xmlschema/#geo"
- xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
- xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
- xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
- xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
- xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >
-
- <verbosity>5</verbosity>
-
-<!-- cfm is 1e-5 for single precision -->
-<!-- erp is typically .1-.8 -->
-<!-- here's the global contact cfm/erp -->
- <physics:ode>
- <stepTime>0.01</stepTime>
- <gravity>0 0 -9.8</gravity>
- <cfm>0.0000000001</cfm>
- <erp>0.2</erp>
- </physics:ode>
-
- <geo:origin>
- <lat>37.4270909558</lat><lon>-122.077919338</lon>
- </geo:origin>
-
- <rendering:gui>
- <type>fltk</type>
- <size>1024 800</size>
- <pos>0 0</pos>
- </rendering:gui>
-
-
- <rendering:ogre>
- <ambient>1.0 1.0 1.0 1.0</ambient>
- <sky>
- <material>Gazebo/CloudySky</material>
- </sky>
- <gazeboPath>media</gazeboPath>
- <grid>false</grid>
- <maxUpdateRate>100</maxUpdateRate>
- </rendering:ogre>
-
-
- <model:physical name="gplane">
- <xyz>0 0 0</xyz>
- <rpy>0 0 0</rpy>
- <static>true</static>
-
- <body:plane name="plane">
- <geom:plane name="plane">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <normal>0 0 1</normal>
- <size>51.3 51.3</size>
- <!-- map3.png -->
- <material>PR2/floor_texture</material>
- </geom:plane>
- </body:plane>
- </model:physical>
-
- <!--
- <model:empty name="ros_model">
- <body:empty name="ros_body">
- <controller:ros_node name="ros_node" plugin="libRos_Node.so">
- <nodeName>simulator_ros_node</nodeName>
- </controller:ros_node>
- </body:empty>
- </model:empty>
- -->
-
- <!-- The "desk"-->
- <model:physical name="desk1_model">
- <xyz> 2.28 -0.21 -0.10</xyz>
- <rpy> 0.0 0.0 0.00</rpy>
- <body:box name="desk1_legs_body">
- <geom:box name="desk1_legs_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <xyz> 0.0 0.0 0.50</xyz>
- <mesh>default</mesh>
- <size>0.5 1.0 0.75</size>
- <mass> 10.0</mass>
- <visual>
- <size> 0.5 1.0 0.75</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- <geom:box name="desk1_top_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <xyz> 0.0 0.0 0.90</xyz>
- <mesh>default</mesh>
- <size>0.75 1.5 0.05</size>
- <mass> 10.0</mass>
- <visual>
- <size> 0.75 1.5 0.05</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
- <!-- The second "desk"-->
- <model:physical name="desk2_model">
- <xyz> 2.25 -3.0 -0.10</xyz>
- <rpy> 0.0 0.0 0.00</rpy>
- <body:box name="desk2_legs_body">
- <geom:box name="desk2_legs_geom">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <xyz> 0.0 0.0 0.50</xyz>
- <mesh>default</mesh>
- <size>0.5 1.0 0.75</size>
- <mass> 10.0</mass>
- <visual>
- <size> 0.5 1.0 0.75</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- <geom:box name="desk2_top_geom">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <xyz> 0.0 0.0 0.90</xyz>
- <mesh>default</mesh>
- <size>0.75 1.5 0.05</size>
- <mass> 10.0</mass>
- <visual>
- <size> 0.75 1.5 0.05</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
- <!-- The small cylinder "cup" -->
- <model:physical name="cylinder1_model">
- <xyz> 2.5 0.0 0.9</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <body:cylinder name="cylinder1_body">
- <geom:cylinder name="cylinder1_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <mesh>default</mesh>
- <size>0.025 0.075</size>
- <mass> 0.05</mass>
- <visual>
- <size> 0.05 0.05 0.075</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_cylinder</mesh>
- </visual>
- </geom:cylinder>
- <geom:box name="cylinder1_base_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <mesh>default</mesh>
- <xyz>0.0 0.0 -0.033</xyz>
- <size>0.05 0.05 0.01</size>
- <mass> 0.01</mass>
- <visual>
- <size> 0.05 0.05 0.01</size>
- <material>Gazebo/Fish</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:cylinder>
- </model:physical>
-
- <!-- The small box "cup" -->
- <model:physical name="object1_model">
- <xyz> 0.835 -0.55 0.95</xyz>
- <rpy> 0.0 0.0 30.0</rpy>
- <body:box name="object1_body">
- <geom:box name="object1_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <mesh>default</mesh>
- <size>0.1 0.03 0.03</size>
- <mass> 0.05</mass>
- <visual>
- <size> 0.1 0.030 0.03</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
-
- <controller:P3D name="p3d_object_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>object1_body</bodyName>
- <interface:position name="p3d_object_position"/>
- </controller:P3D>
-
- </model:physical>
-
-
- <!-- The small ball -->
- <model:physical name="sphere1_model">
- <xyz> 2.5 -2.8 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <body:sphere name="sphere1_body">
- <geom:sphere name="sphere1_geom">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <mesh>default</mesh>
- <size> 0.15</size>
- <mass> 1.0</mass>
- <visual>
- <size> 0.3 0.3 0.3</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_sphere</mesh>
- </visual>
- </geom:sphere>
- </body:sphere>
- </model:physical>
-
- <!-- The large ball map3.png -->
- <model:physical name="sphere2_model">
- <xyz> 5.85 4.35 1.55</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <body:sphere name="sphere2_body">
- <geom:sphere name="sphere2_geom">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <mesh>default</mesh>
- <size> 1.0</size>
- <mass> 1.0</mass>
- <visual>
- <size> 2.0 2.0 2.0</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_sphere</mesh>
- </visual>
- </geom:sphere>
- </body:sphere>
- </model:physical>
-
- <!-- The wall in front map3.png -->
- <model:physical name="wall_2_model">
- <xyz> 11.6 -1.55 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <static>true</static>
- <body:box name="wall_2_body">
- <geom:box name="wall_2_geom">
- <mesh>default</mesh>
- <size>2.1 32.8 2.0</size>
- <visual>
- <size>2.1 32.8 2.0</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
- <!-- The wall behind -->
- <model:physical name="wall_1_model">
- <xyz> -11.3 -1.45 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <static>true</static>
- <body:box name="wall_1_body">
- <geom:box name="wall_1_geom">
- <mesh>default</mesh>
- <size>0.4 24.0 2.0</size>
- <visual>
- <size>0.4 24.0 2.0</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
- <!-- The wall 3 -->
- <model:physical name="wall_3_model">
- <xyz> 6.7 8.05 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <static>true</static>
- <body:box name="wall_3_body">
- <geom:box name="wall_3_geom">
- <mesh>default</mesh>
- <size>7.5 1.2 2.0</size>
- <visual>
- <size>7.5 1.2 2.0</size>
- <material>Gazebo/Chrome</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
-
-
- <model:physical name="robot_model1">
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
- <rpy>0.0 0.0 0.0 </rpy>
-
- <!-- base, torso and arms -->
- <include embedded="true">
- <xi:include href="pr2_xml_rosgazebo.model" />
- </include>
-
- </model:physical>
-
-
- <!-- White Directional light -->
- <model:renderable name="directional_white">
- <light>
- <type>directional</type>
- <direction>0 -0.5 -0.5</direction>
- <diffuseColor>0.4 0.4 0.4</diffuseColor>
- <specularColor>0.0 0.0 0.0</specularColor>
- <attenuation>1 0.0 1.0 0.4</attenuation>
- </light>
- </model:renderable>
-
-
-</gazebo:world>
Deleted: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo_wg.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo_wg.world 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_rosgazebo_wg.world 2008-09-09 21:27:00 UTC (rev 4114)
@@ -1,120 +0,0 @@
-<?xml version="1.0"?>
-
-<gazebo:world
- xmlns:xi="http://www.w3.org/2001/XInclude"
- xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
- xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
- xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window"
- xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param"
- xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
- xmlns:geo="http://willowgarage.com/xmlschema/#geo"
- xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
- xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
- xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
- xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
- xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >
-
- <verbosity>5</verbosity>
-
-<!-- cfm is 1e-5 for single precision -->
-<!-- erp is typically .1-.8 -->
-<!-- here's the global contact cfm/erp -->
- <physics:ode>
- <stepTime>0.01</stepTime>
- <gravity>0 0 -9.8</gravity>
- <cfm>0.0000000001</cfm>
- <erp>0.2</erp>
- </physics:ode>
-
- <geo:origin>
- <lat>37.4270909558</lat><lon>-122.077919338</lon>
- </geo:origin>
-
- <rendering:gui>
- <type>fltk</type>
- <size>1024 800</size>
- <pos>0 0</pos>
- </rendering:gui>
-
-
- <rendering:ogre>
- <ambient>1.0 1.0 1.0 1.0</ambient>
- <sky>
- <material>Gazebo/CloudySky</material>
- </sky>
- <gazeboPath>media</gazeboPath>
- <grid>false</grid>
- <maxUpdateRate>100</maxUpdateRate>
- </rendering:ogre>
-
- <model:physical name="gplane">
- <xyz>0 0 0</xyz>
- <rpy>0 0 0</rpy>
- <static>true</static>
-
- <body:plane name="plane">
- <geom:plane name="plane">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <normal>0 0 1</normal>
- <size>51.3 51.3</size>
- <material>Gazebo/GrassFloor</material>
- </geom:plane>
- </body:plane>
- </model:physical>
-
-<!--
- <model:physical name="walls">
- <include embedded="false">
- <xi:include href="willow-walls.model" />
- </include>
- </model:physical>
--->
- <model:physical name="map">
- <xyz>-25.65 25.65 1.0</xyz>
- <rpy>180 0 0</rpy>
- <body:map name="map_body">
- <geom:map name="map_geom">
- <image>willowMap.png</image>
- <threshold>200</threshold>
- <granularity>2</granularity>
- <negative>false</negative>
- <scale>0.1</scale>
- <offset>0 0 0</offset>
- <material>Gazebo/Rocky</material>
- </geom:map>
- </body:map>
- </model:physical>
-
-
- <model:physical name="robot_model1">
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
- <rpy>0.0 0.0 0.0 </rpy>
-
- <!-- base, torso and arms -->
- <include embedded="true">
- <xi:include href="pr2_xml_rosgazebo.model" />
- </include>
-
- </model:physical>
-
-
- <!-- White Directional light -->
- <!--
- <model:renderable name="directional_white">
- <light>
- <type>directional</type>
- <direction>0 -0.5 -0.5</direction>
- <diffuseColor>0.4 0.4 0.4</diffuseColor>
- <specularColor>0.0 0.0 0.0</specularColor>
- <attenuation>1 0.0 1.0 0.4</attenuation>
- </light>
- </model:renderable>
- -->
-
-
-</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world 2008-09-09 21:26:57 UTC (rev 4113)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world 2008-09-09 21:27:00 UTC (rev 4114)
@@ -346,7 +346,7 @@
<!-- base, torso and arms -->
<include embedded="true">
- <xi:include href="pr2_xml_rosgazebo.model" />
+ <xi:include href="pr2_xml_test.model" />
</include>
</model:physical>
Added: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_nolimit.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_nolimit.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_nolimit.world 2008-09-09 21:27:00 UTC (rev 4114)
@@ -0,0 +1,332 @@
+<?xml version="1.0"?>
+
+<gazebo:world
+ xmlns:xi="http://www.w3.org/2001/XInclude"
+ xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
+ xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
+ xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+ xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window"
+ xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param"
+ xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
+ xmlns:geo="http://willowgarage.com/xmlschema/#geo"
+ xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
+ xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
+ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+ xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
+ xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
+ xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
+ xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+ xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >
+
+ <verbosity>5</verbosity>
+
+<!-- cfm is 1e-5 for single precision -->
+<!-- erp is typically .1-.8 -->
+<!-- here's the global contact cfm/erp -->
+ <physics:ode>
+ <stepTime>0.01</stepTime>
+ <gravity>0 0 -9.8</gravity>
+ <cfm>0.0000000001</cfm>
+ <erp>0.2</erp>
+ <quickStep>false</quickStep>
+ </physics:ode>
+
+ <geo:origin>
+ <lat>37.4270909558</lat><lon>-122.077919338</lon>
+ </geo:origin>
+
+ <rendering:gui>
+ <type>fltk</type>
+ <size>1024 800</size>
+ <pos>0 0</pos>
+ </rendering:gui>
+
+
+ <rendering:ogre>
+ <ambient>1.0 1.0 1.0 1.0</ambient>
+ <sky>
+ <material>Gazebo/CloudySky</material>
+ </sky>
+ <gazeboPath>media</gazeboPath>
+ <grid>false</grid>
+ <maxUpdateRate>100</maxUpdateRate>
+ </rendering:ogre>
+
+
+ <model:physical name="gplane">
+ <xyz>0 0 0</xyz>
+ <rpy>0 0 0</rpy>
+ <static>true</static>
+
+ <body:plane name="plane">
+ <geom:plane name="plane">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <normal>0 0 1</normal>
+ <size>51.3 51.3</size>
+ <!-- map3.png -->
+ <material>PR2/floor_texture</material>
+ </geom:plane>
+ </body:plane>
+ </model:physical>
+
+ <!--
+ <model:empty name="ros_model">
+ <body:empty name="ros_body">
+ <controller:ros_node name="ros_node" plugin="libRos_Node.so">
+ <nodeName>simulator_ros_node</nodeName>
+ </controller:ros_node>
+ </body:empty>
+ </model:empty>
+ -->
+
+ <!-- The "desk"-->
+ <model:physical name="desk1_model">
+ <xyz> 2.28 -0.21 -0.10</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <body:box name="desk1_legs_body">
+ <geom:box name="desk1_legs_geom">
+ <kp>100000000.0</kp>
+ <kd>1.0</kd>
+ <xyz> 0.0 0.0 0.50</xyz>
+ <mesh>default</mesh>
+ <size>0.5 1.0 0.75</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.5 1.0 0.75</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="desk1_top_geom">
+ <kp>100000000.0</kp>
+ <kd>0.1</kd>
+ <xyz> 0.0 0.0 0.90</xyz>
+ <mesh>default</mesh>
+ <size>0.75 1.5 0.05</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.75 1.5 0.05</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The second "desk"-->
+ <model:physical name="desk2_model">
+ <xyz> 2.25 -3.0 -0.10</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <body:box name="desk2_legs_body">
+ <geom:box name="desk2_legs_geom">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <xyz> 0.0 0.0 0.50</xyz>
+ <mesh>default</mesh>
+ <size>0.5 1.0 0.75</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.5 1.0 0.75</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="desk2_top_geom">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <xyz> 0.0 0.0 0.90</xyz>
+ <mesh>default</mesh>
+ <size>0.75 1.5 0.05</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.75 1.5 0.05</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The sm...
[truncated message content] |
|
From: <hsu...@us...> - 2008-09-09 23:14:50
|
Revision: 4126
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4126&view=rev
Author: hsujohnhsu
Date: 2008-09-09 23:14:57 +0000 (Tue, 09 Sep 2008)
Log Message:
-----------
updates to new gazebo revision.
more clean up on local patch.
Modified Paths:
--------------
pkg/trunk/3rdparty/gazebo/Makefile
pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
Modified: pkg/trunk/3rdparty/gazebo/Makefile
===================================================================
--- pkg/trunk/3rdparty/gazebo/Makefile 2008-09-09 22:31:20 UTC (rev 4125)
+++ pkg/trunk/3rdparty/gazebo/Makefile 2008-09-09 23:14:57 UTC (rev 4126)
@@ -2,7 +2,7 @@
SVN_DIR = gazebo-svn
SVN_URL = https://playerstage.svn.sourceforge.net/svnroot/playerstage/code/gazebo/trunk
-SVN_REVISION = -r 6981
+SVN_REVISION = -r 7016
SVN_PATCH = gazebo_patch.diff
include $(shell rospack find mk)/svn_checkout.mk
Modified: pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
===================================================================
--- pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-09-09 22:31:20 UTC (rev 4125)
+++ pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-09-09 23:14:57 UTC (rev 4126)
@@ -1,10 +1,10 @@
Index: player/SConscript
===================================================================
---- player/SConscript (revision 6981)
+--- player/SConscript (revision 7016)
+++ player/SConscript (working copy)
@@ -1,7 +1,8 @@
import os
- Import('env install_prefix staticObjs sharedObjs subdirs')
+ Import('env install_prefix sharedObjs subdirs')
-parseConfigs = ['pkg-config --cflags --libs playerc++']
+parseConfigs = ['pkg-config --cflags --libs playerc++',
@@ -14,9 +14,9 @@
'GazeboClient.cc',
Index: libgazebo/gazebo.h
===================================================================
---- libgazebo/gazebo.h (revision 6981)
+--- libgazebo/gazebo.h (revision 7016)
+++ libgazebo/gazebo.h (working copy)
-@@ -558,7 +558,7 @@
+@@ -556,7 +556,7 @@
/// Maximum image pixels (width x height)
@@ -25,7 +25,7 @@
/// \brief Camera interface data
class CameraData
-@@ -586,6 +586,9 @@
+@@ -584,6 +584,9 @@
/// Pose of the camera
public: Pose camera_pose;
@@ -35,7 +35,7 @@
};
/// \brief The camera interface
-@@ -604,6 +607,7 @@
+@@ -602,6 +605,7 @@
{
Iface::Create(server,id);
this->data = (CameraData*)this->mMap;
@@ -43,7 +43,7 @@
}
/// \brief Open an existing interface
-@@ -613,8 +617,18 @@
+@@ -611,8 +615,18 @@
{
Iface::Open(client,id);
this->data = (CameraData*)this->mMap;
@@ -62,7 +62,7 @@
/// Pointer to the camera data
public: CameraData *data;
};
-@@ -833,6 +847,9 @@
+@@ -831,6 +845,9 @@
/// Commaned range count
public: int cmd_range_count;
@@ -72,7 +72,7 @@
};
/// \brief Laser interface
-@@ -851,6 +868,7 @@
+@@ -849,6 +866,7 @@
{
Iface::Create(server,id);
this->data = (LaserData*)this->mMap;
@@ -80,7 +80,7 @@
}
/// \brief Open an existing interface
-@@ -860,8 +878,16 @@
+@@ -858,8 +876,16 @@
{
Iface::Open(client,id);
this->data = (LaserData*)this->mMap;
@@ -97,7 +97,7 @@
/// Pointer to the laser data
public: LaserData *data;
};
-@@ -1065,6 +1091,30 @@
+@@ -1063,6 +1089,30 @@
/// Lift down flag
public: int lift_down;
@@ -128,7 +128,7 @@
};
/// \brief Gripper interface
-@@ -1262,6 +1312,8 @@
+@@ -1260,6 +1310,8 @@
/// \} */
@@ -137,7 +137,7 @@
/***************************************************************************/
/// \addtogroup libgazebo_iface
/// \{
-@@ -1342,7 +1394,7 @@
+@@ -1340,7 +1392,7 @@
\{
*/
@@ -146,7 +146,7 @@
#define GAZEBO_STEREO_CAMERA_MAX_DISPARITY_SIZE 640 * 480
/// \brief Stereo data
-@@ -1380,6 +1432,9 @@
+@@ -1378,6 +1430,9 @@
/// Right depth map (float)
public: float right_depth[GAZEBO_STEREO_CAMERA_MAX_DISPARITY_SIZE];
@@ -156,7 +156,7 @@
};
-@@ -1397,6 +1452,7 @@
+@@ -1395,6 +1450,7 @@
{
Iface::Create(server,id);
this->data = (StereoCameraData*)this->mMap;
@@ -164,7 +164,7 @@
}
/// \brief Open the iface
-@@ -1404,8 +1460,16 @@
+@@ -1402,8 +1458,16 @@
{
Iface::Open(client,id);
this->data = (StereoCameraData*)this->mMap;
@@ -183,13 +183,14 @@
};
Index: server/physics/SphereGeom.cc
===================================================================
---- server/physics/SphereGeom.cc (revision 6981)
+--- server/physics/SphereGeom.cc (revision 7016)
+++ server/physics/SphereGeom.cc (working copy)
-@@ -55,10 +55,18 @@
- this->radiusP->Load(node);
+@@ -66,11 +66,18 @@
+ this->radiusP->SetValue( radius );
// Initialize box mass matrix
-- dMassSetSphereTotal(&this->mass, this->massP->GetValue(), this->radiusP->GetValue());
+- dMassSetSphereTotal(&this->mass, this->massP->GetValue(),
+- this->radiusP->GetValue());
+ this->SetGeom( dCreateSphere(0, this->radiusP->GetValue()), true);
// Create the sphere geometry
@@ -205,27 +206,18 @@
+
}
- //////////////////////////////////////////////////////////////////////////////
+ ////////////////////////////////////////////////////////////////////////////////
Index: server/physics/BoxGeom.cc
===================================================================
---- server/physics/BoxGeom.cc (revision 6981)
+--- server/physics/BoxGeom.cc (revision 7016)
+++ server/physics/BoxGeom.cc (working copy)
-@@ -54,16 +54,25 @@
- {
- this->sizeP->Load(node);
+@@ -66,9 +66,18 @@
+ this->sizeP->SetValue( size );
-- // Initialize box mass matrix
-- dMassSetBoxTotal(&this->mass, this->massP->GetValue(),
-- this->sizeP->GetValue().x,
-- this->sizeP->GetValue().y,
+ // Initialize box mass matrix
+- dMassSetBoxTotal(&this->mass, this->massP->GetValue(),
+- this->sizeP->GetValue().x, this->sizeP->GetValue().y,
- this->sizeP->GetValue().z);
--
- // Create a box geometry with box mass matrix
- this->SetGeom(dCreateBox( 0, this->sizeP->GetValue().x,
- this->sizeP->GetValue().y,
- this->sizeP->GetValue().z), true );
-+
-+ // Initialize box mass matrix
+ // set mass matrix if user provides some info
+ // pending a tag <massMatrix>true</massMatrix> in geom:
+ if (this->customMassMatrix)
@@ -234,80 +226,72 @@
+ this->ixx,this->iyy,this->izz,
+ this->ixy,this->ixz,this->iyz);
+ else
-+ dMassSetBoxTotal(&this->mass, this->massP->GetValue(),
-+ this->sizeP->GetValue().x,
-+ this->sizeP->GetValue().y,
++ // Initialize box mass matrix
++ dMassSetBoxTotal(&this->mass, this->massP->GetValue(),
++ this->sizeP->GetValue().x, this->sizeP->GetValue().y,
+ this->sizeP->GetValue().z);
-+
- }
- //////////////////////////////////////////////////////////////////////////////
+
+ // Create a box geometry with box mass matrix
Index: server/physics/Geom.hh
===================================================================
---- server/physics/Geom.hh (revision 6981)
+--- server/physics/Geom.hh (revision 7016)
+++ server/physics/Geom.hh (working copy)
-@@ -168,6 +168,20 @@
+@@ -171,6 +171,20 @@
/// Mass as a double
- protected: Param<double> *massP;
+ protected: ParamT<double> *massP;
+ /// User specified Mass Matrix
-+ protected: Param<bool> *customMassMatrixP;
-+ protected: Param<double> *cxP ;
-+ protected: Param<double> *cyP ;
-+ protected: Param<double> *czP ;
-+ protected: Param<double> *ixxP;
-+ protected: Param<double> *iyyP;
-+ protected: Param<double> *izzP;
-+ protected: Param<double> *ixyP;
-+ protected: Param<double> *ixzP;
-+ protected: Param<double> *iyzP;
++ protected: ParamT<bool> *customMassMatrixP;
++ protected: ParamT<double> *cxP ;
++ protected: ParamT<double> *cyP ;
++ protected: ParamT<double> *czP ;
++ protected: ParamT<double> *ixxP;
++ protected: ParamT<double> *iyyP;
++ protected: ParamT<double> *izzP;
++ protected: ParamT<double> *ixyP;
++ protected: ParamT<double> *ixzP;
++ protected: ParamT<double> *iyzP;
+ protected: bool customMassMatrix;
+ protected: double cx,cy,cz,ixx,iyy,izz,ixy,ixz,iyz;
+
- private: Param<Vector3> *xyzP;
- private: Param<Quatern> *rpyP;
+ private: ParamT<Vector3> *xyzP;
+ private: ParamT<Quatern> *rpyP;
Index: server/physics/Body.hh
===================================================================
---- server/physics/Body.hh (revision 6981)
+--- server/physics/Body.hh (revision 7016)
+++ server/physics/Body.hh (working copy)
-@@ -170,6 +170,7 @@
+@@ -180,6 +180,7 @@
- private: Param<Vector3> *xyzP;
- private: Param<Quatern> *rpyP;
-+ private: Param<bool> *turnGravityOffP;
+ private: ParamT<Vector3> *xyzP;
+ private: ParamT<Quatern> *rpyP;
++ private: ParamT<bool> *turnGravityOffP;
};
/// \}
Index: server/physics/HingeJoint.hh
===================================================================
---- server/physics/HingeJoint.hh (revision 6981)
+--- server/physics/HingeJoint.hh (revision 7016)
+++ server/physics/HingeJoint.hh (working copy)
@@ -126,6 +126,7 @@
- private: Param<Vector3> *axisP;
- private: Param<Angle> *loStopP;
- private: Param<Angle> *hiStopP;
-+ private: Param<Vector3> *anchorOffsetP;
+ private: ParamT<Vector3> *axisP;
+ private: ParamT<Angle> *loStopP;
+ private: ParamT<Angle> *hiStopP;
++ private: ParamT<Vector3> *anchorOffsetP;
};
/// \}
Index: server/physics/CylinderGeom.cc
===================================================================
---- server/physics/CylinderGeom.cc (revision 6981)
+--- server/physics/CylinderGeom.cc (revision 7016)
+++ server/physics/CylinderGeom.cc (working copy)
-@@ -51,13 +51,22 @@
- {
- this->sizeP->Load(node);
+@@ -64,11 +64,21 @@
+ this->sizeP->SetValue( size );
-- // Initialize mass matrix
+ // Initialize mass matrix
- dMassSetCylinderTotal(&this->mass, this->massP->GetValue(), 3,
- this->sizeP->GetValue().x, this->sizeP->GetValue().y);
--
-+ // create a cylinder geometry
- this->SetGeom( dCreateCylinder( 0, this->sizeP->GetValue().x,
- this->sizeP->GetValue().y ), true );
-
-+ // Initialize mass matrix
+ // pending a tag <massMatrix>true</massMatrix> in geom:
+ if (this->customMassMatrix)
+ dMassSetParameters(&this->mass, this->massP->GetValue(),
@@ -315,8 +299,12 @@
+ this->ixx,this->iyy,this->izz,
+ this->ixy,this->ixz,this->iyz);
+ else
++ // Initialize mass matrix
+ dMassSetCylinderTotal(&this->mass, this->massP->GetValue(), 3,
+ this->sizeP->GetValue().x, this->sizeP->GetValue().y);
+
+ this->SetGeom( dCreateCylinder( 0, this->sizeP->GetValue().x,
+ this->sizeP->GetValue().y ), true );
+
+
}
@@ -324,27 +312,27 @@
//////////////////////////////////////////////////////////////////////////////
Index: server/physics/Geom.cc
===================================================================
---- server/physics/Geom.cc (revision 6981)
+--- server/physics/Geom.cc (revision 7016)
+++ server/physics/Geom.cc (working copy)
-@@ -66,6 +66,17 @@
- this->rpyP = new Param<Quatern>("rpy", Quatern(), 0);
- this->laserFiducialIdP = new Param<int>("laserFiducialId",-1,0);
- this->laserRetroP = new Param<float>("laserRetro",-1,0);
+@@ -73,6 +73,17 @@
+
+ this->laserFiducialIdP = new ParamT<int>("laserFiducialId",-1,0);
+ this->laserRetroP = new ParamT<float>("laserRetro",-1,0);
+
-+ this->customMassMatrixP = new Param<bool>("massMatrix",false,0);
-+ this->cxP = new Param<double>("cx",0.0,0);
-+ this->cyP = new Param<double>("cy",0.0,0);
-+ this->czP = new Param<double>("cz",0.0,0);
-+ this->ixxP = new Param<double>("ixx",1e-6,0);
-+ this->iyyP = new Param<double>("iyy",1e-6,0);
-+ this->izzP = new Param<double>("izz",1e-6,0);
-+ this->ixyP = new Param<double>("ixy",0.0,0);
-+ this->ixzP = new Param<double>("ixz",0.0,0);
-+ this->iyzP = new Param<double>("iyz",0.0,0);
++ this->customMassMatrixP = new ParamT<bool>("massMatrix",false,0);
++ this->cxP = new ParamT<double>("cx",0.0,0);
++ this->cyP = new ParamT<double>("cy",0.0,0);
++ this->czP = new ParamT<double>("cz",0.0,0);
++ this->ixxP = new ParamT<double>("ixx",1e-6,0);
++ this->iyyP = new ParamT<double>("iyy",1e-6,0);
++ this->izzP = new ParamT<double>("izz",1e-6,0);
++ this->ixyP = new ParamT<double>("ixy",0.0,0);
++ this->ixzP = new ParamT<double>("ixz",0.0,0);
++ this->iyzP = new ParamT<double>("iyz",0.0,0);
+ Param::End();
}
- ////////////////////////////////////////////////////////////////////////////////
-@@ -91,6 +102,16 @@
+@@ -99,6 +110,16 @@
delete this->rpyP;
delete this->laserFiducialIdP;
delete this->laserRetroP;
@@ -361,7 +349,7 @@
}
////////////////////////////////////////////////////////////////////////////////
-@@ -115,6 +136,30 @@
+@@ -123,6 +144,30 @@
this->massP->SetValue( 0.001 );
}
@@ -392,7 +380,7 @@
this->contact->Load(node);
this->LoadChild(node);
-@@ -393,18 +438,21 @@
+@@ -401,18 +446,21 @@
if (!this->placeable)
return NULL;
@@ -418,17 +406,17 @@
dMassRotate(&this->bodyMass, r);
Index: server/physics/Body.cc
===================================================================
---- server/physics/Body.cc (revision 6981)
+--- server/physics/Body.cc (revision 7016)
+++ server/physics/Body.cc (working copy)
-@@ -66,6 +66,7 @@
+@@ -70,6 +70,7 @@
- this->xyzP = new Param<Vector3>("xyz", Vector3(), 0);
- this->rpyP = new Param<Quatern>("rpy", Quatern(), 0);
-+ this->turnGravityOffP = new Param<bool>("turnGravityOff", false, 0);
+ this->rpyP = new ParamT<Quatern>("rpy", Quatern(), 0);
+ this->rpyP->Callback( &Body::SetRotation, this );
++ this->turnGravityOffP = new ParamT<bool>("turnGravityOff", false, 0);
+ Param::End();
}
-
-@@ -102,6 +103,7 @@
+@@ -107,6 +108,7 @@
this->nameP->Load(node);
this->xyzP->Load(node);
this->rpyP->Load(node);
@@ -436,7 +424,7 @@
Pose3d initPose;
initPose.pos = **(this->xyzP);
-@@ -129,8 +131,9 @@
+@@ -134,8 +136,9 @@
}
// If no geoms are attached, then don't let gravity affect the body.
@@ -449,17 +437,17 @@
Index: server/physics/HingeJoint.cc
===================================================================
---- server/physics/HingeJoint.cc (revision 6981)
+--- server/physics/HingeJoint.cc (revision 7016)
+++ server/physics/HingeJoint.cc (working copy)
-@@ -43,6 +43,7 @@
- this->axisP = new Param<Vector3>("axis",Vector3(0,1,0), 1);
- this->loStopP = new Param<Angle>("lowStop",-M_PI,0);
- this->hiStopP = new Param<Angle>("highStop",M_PI,0);
-+ this->anchorOffsetP = new Param<Vector3>("anchorOffset",Vector3(0,0,0),0);
+@@ -44,6 +44,7 @@
+ this->axisP = new ParamT<Vector3>("axis",Vector3(0,1,0), 1);
+ this->loStopP = new ParamT<Angle>("lowStop",-M_PI,0);
+ this->hiStopP = new ParamT<Angle>("highStop",M_PI,0);
++ this->anchorOffsetP = new ParamT<Vector3>("anchorOffset",Vector3(0,0,0),0);
+ Param::End();
}
-
-@@ -62,6 +63,7 @@
+@@ -64,6 +65,7 @@
this->axisP->Load(node);
this->loStopP->Load(node);
this->hiStopP->Load(node);
@@ -467,7 +455,7 @@
// Perform this three step ordering to ensure the parameters are set
// properly. This is taken from the ODE wiki.
-@@ -131,7 +133,7 @@
+@@ -133,7 +135,7 @@
// Set the anchor point
void HingeJoint::SetAnchor( const Vector3 &anchor )
{
@@ -478,29 +466,29 @@
Index: server/physics/ode/ODEPhysics.hh
===================================================================
---- server/physics/ode/ODEPhysics.hh (revision 6981)
+--- server/physics/ode/ODEPhysics.hh (revision 7016)
+++ server/physics/ode/ODEPhysics.hh (working copy)
@@ -133,6 +133,7 @@
- private: Param<double> *globalCFMP;
- private: Param<double> *globalERPP;
-+ private: Param<bool> *quickStepP;
+ private: ParamT<double> *globalCFMP;
+ private: ParamT<double> *globalERPP;
++ private: ParamT<bool> *quickStepP;
};
/** \}*/
Index: server/physics/ode/ODEPhysics.cc
===================================================================
---- server/physics/ode/ODEPhysics.cc (revision 6981)
+--- server/physics/ode/ODEPhysics.cc (revision 7016)
+++ server/physics/ode/ODEPhysics.cc (working copy)
-@@ -69,6 +69,7 @@
-
- this->globalCFMP = new Param<double>("cfm", 10e-5, 0);
- this->globalERPP = new Param<double>("erp", 0.2, 0);
-+ this->quickStepP = new Param<bool>("quickStep", false, 0);
+@@ -70,6 +70,7 @@
+ Param::Begin(&this->parameters);
+ this->globalCFMP = new ParamT<double>("cfm", 10e-5, 0);
+ this->globalERPP = new ParamT<double>("erp", 0.2, 0);
++ this->quickStepP = new ParamT<bool>("quickStep", false, 0);
+ Param::End();
}
- ////////////////////////////////////////////////////////////////////////////////
-@@ -86,6 +87,7 @@
+@@ -88,6 +89,7 @@
delete this->globalCFMP;
delete this->globalERPP;
@@ -508,7 +496,7 @@
}
////////////////////////////////////////////////////////////////////////////////
-@@ -101,6 +103,7 @@
+@@ -103,6 +105,7 @@
this->updateRateP->Load(cnode);
this->globalCFMP->Load(cnode);
this->globalERPP->Load(cnode);
@@ -516,7 +504,7 @@
}
////////////////////////////////////////////////////////////////////////////////
-@@ -113,6 +116,7 @@
+@@ -115,6 +118,7 @@
stream << prefix << " " << *(this->updateRateP) << "\n";
stream << prefix << " " << *(this->globalCFMP) << "\n";
stream << prefix << " " << *(this->globalERPP) << "\n";
@@ -524,7 +512,7 @@
stream << prefix << "</physics:ode>\n";
}
-@@ -135,8 +139,10 @@
+@@ -137,8 +141,10 @@
dSpaceCollide( this->spaceId, this, CollisionCallback );
// Update the dynamical model
@@ -537,7 +525,7 @@
// Very important to clear out the contact group
dJointGroupEmpty( this->contactGroup );
-@@ -264,15 +270,16 @@
+@@ -266,15 +272,16 @@
contact.surface.mode = dContactSlip1 | dContactSlip2 |
dContactSoftERP | dContactSoftCFM |
dContactBounce | dContactMu2 | dContactApprox1;
@@ -558,9 +546,9 @@
contact.surface.mu2 = MIN(geom1->contact->mu2, geom2->contact->mu2);
Index: server/physics/TrimeshGeom.cc
===================================================================
---- server/physics/TrimeshGeom.cc (revision 6981)
+--- server/physics/TrimeshGeom.cc (revision 7016)
+++ server/physics/TrimeshGeom.cc (working copy)
-@@ -206,7 +206,13 @@
+@@ -208,7 +208,13 @@
this->geomId = dCreateTriMesh( this->spaceId, this->odeData,0,0,0 );
@@ -577,7 +565,7 @@
this->SetGeom(this->geomId, true);
Index: server/sensors/Sensor.hh
===================================================================
---- server/sensors/Sensor.hh (revision 6981)
+--- server/sensors/Sensor.hh (revision 7016)
+++ server/sensors/Sensor.hh (working copy)
@@ -70,6 +70,7 @@
@@ -597,9 +585,9 @@
#endif
Index: server/sensors/ray/RaySensor.cc
===================================================================
---- server/sensors/ray/RaySensor.cc (revision 6981)
+--- server/sensors/ray/RaySensor.cc (revision 7016)
+++ server/sensors/ray/RaySensor.cc (working copy)
-@@ -271,7 +271,7 @@
+@@ -273,7 +273,7 @@
// Update the sensor information
void RaySensor::UpdateChild()
{
@@ -610,7 +598,7 @@
Pose3d poseDelta;
Index: server/sensors/Sensor.cc
===================================================================
---- server/sensors/Sensor.cc (revision 6981)
+--- server/sensors/Sensor.cc (revision 7016)
+++ server/sensors/Sensor.cc (working copy)
@@ -33,6 +33,7 @@
#include "ControllerFactory.hh"
@@ -620,7 +608,7 @@
using namespace gazebo;
-@@ -69,6 +70,14 @@
+@@ -71,6 +72,14 @@
this->LoadController( node->GetChildByNSPrefix("controller") );
this->LoadChild(node);
@@ -635,7 +623,7 @@
}
////////////////////////////////////////////////////////////////////////////////
-@@ -183,4 +192,11 @@
+@@ -185,4 +194,11 @@
this->active = value;
}
@@ -649,7 +637,7 @@
+
Index: server/Simulator.cc
===================================================================
---- server/Simulator.cc (revision 6981)
+--- server/Simulator.cc (revision 7016)
+++ server/Simulator.cc (working copy)
@@ -72,6 +72,7 @@
timeout(-1),
@@ -670,7 +658,7 @@
currTime - this->prevPhysicsTime >= physicsUpdatePeriod)
{
@@ -315,6 +319,9 @@
- this->prevPhysicsTime = this->GetRealTime();
+ World::Instance()->Update();
}
+ //double tmpT2 = this->GetWallTime();
@@ -681,7 +669,7 @@
currTime - this->prevRenderTime >= renderUpdatePeriod)
Index: server/XMLConfig.cc
===================================================================
---- server/XMLConfig.cc (revision 6981)
+--- server/XMLConfig.cc (revision 7016)
+++ server/XMLConfig.cc (working copy)
@@ -513,29 +513,59 @@
///////////////////////////////////////////////////////////////////////////
@@ -759,7 +747,7 @@
Index: server/GazeboConfig.cc
===================================================================
---- server/GazeboConfig.cc (revision 6981)
+--- server/GazeboConfig.cc (revision 7016)
+++ server/GazeboConfig.cc (working copy)
@@ -67,31 +67,34 @@
this->gazeboPaths.push_back(gazebo_resource_path);
@@ -835,7 +823,7 @@
}
Index: server/gui/StatusBar.cc
===================================================================
---- server/gui/StatusBar.cc (revision 6981)
+--- server/gui/StatusBar.cc (revision 7016)
+++ server/gui/StatusBar.cc (working copy)
@@ -25,6 +25,7 @@
*/
@@ -847,7 +835,7 @@
#include <FL/Fl_Button.H>
Index: server/gui/GLWindow.cc
===================================================================
---- server/gui/GLWindow.cc (revision 6981)
+--- server/gui/GLWindow.cc (revision 7016)
+++ server/gui/GLWindow.cc (working copy)
@@ -227,21 +227,10 @@
}
@@ -877,7 +865,7 @@
{
Index: server/World.hh
===================================================================
---- server/World.hh (revision 6981)
+--- server/World.hh (revision 7016)
+++ server/World.hh (working copy)
@@ -92,6 +92,26 @@
/// \return Pointer to the physics engine
@@ -918,7 +906,7 @@
};
Index: server/controllers/camera/generic/Generic_Camera.cc
===================================================================
---- server/controllers/camera/generic/Generic_Camera.cc (revision 6981)
+--- server/controllers/camera/generic/Generic_Camera.cc (revision 7016)
+++ server/controllers/camera/generic/Generic_Camera.cc (working copy)
@@ -86,7 +86,24 @@
// Update the controller
@@ -948,9 +936,9 @@
////////////////////////////////////////////////////////////////////////////////
Index: server/controllers/Controller.cc
===================================================================
---- server/controllers/Controller.cc (revision 6981)
+--- server/controllers/Controller.cc (revision 7016)
+++ server/controllers/Controller.cc (working copy)
-@@ -73,11 +73,15 @@
+@@ -75,11 +75,15 @@
this->typeName = node->GetName();
this->nameP->Load(node);
@@ -971,9 +959,9 @@
// Create the interfaces
Index: server/controllers/ptz/generic/Generic_PTZ.cc
===================================================================
---- server/controllers/ptz/generic/Generic_PTZ.cc (revision 6981)
+--- server/controllers/ptz/generic/Generic_PTZ.cc (revision 7016)
+++ server/controllers/ptz/generic/Generic_PTZ.cc (working copy)
-@@ -68,10 +68,10 @@
+@@ -70,10 +70,10 @@
// Destructor
Generic_PTZ::~Generic_PTZ()
{
@@ -990,7 +978,7 @@
this->tiltJoint = NULL;
Index: server/World.cc
===================================================================
---- server/World.cc (revision 6981)
+--- server/World.cc (revision 7016)
+++ server/World.cc (working copy)
@@ -27,6 +27,7 @@
#include <assert.h>
@@ -1112,7 +1100,7 @@
int World::LoadEntities(XMLConfigNode *node, Model *parent)
Index: SConstruct
===================================================================
---- SConstruct (revision 6981)
+--- SConstruct (revision 7016)
+++ SConstruct (working copy)
@@ -22,8 +22,9 @@
# 3rd party packages
@@ -1125,7 +1113,7 @@
'fltk-config --cflags --libs --ldflags --use-gl --use-images',
'pkg-config --cflags --libs xft'
]
-@@ -80,7 +81,7 @@
+@@ -81,7 +82,7 @@
rcconfig = env.RCConfig(target='gazeborc', source=Value(install_prefix))
# DEFAULT list of subdirectories to build
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh 2008-09-09 22:31:20 UTC (rev 4125)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/Ros_PTZ.hh 2008-09-09 23:14:57 UTC (rev 4126)
@@ -114,13 +114,13 @@
private: float cmdTilt;
private: float cmdPan;
- private: Param<double> *motionGainP;
- private: Param<double> *forceP;
+ private: ParamT<double> *motionGainP;
+ private: ParamT<double> *forceP;
- private: Param<std::string> *panJointNameP;
- private: Param<std::string> *tiltJointNameP;
- private: Param<std::string> *commandTopicNameP;
- private: Param<std::string> *stateTopicNameP;
+ private: ParamT<std::string> *panJointNameP;
+ private: ParamT<std::string> *tiltJointNameP;
+ private: ParamT<std::string> *commandTopicNameP;
+ private: ParamT<std::string> *stateTopicNameP;
// pointer to ros node
private: ros::node *rosnode;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc 2008-09-09 22:31:20 UTC (rev 4125)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_PTZ.cc 2008-09-09 23:14:57 UTC (rev 4126)
@@ -59,12 +59,14 @@
this->panJoint = NULL;
this->tiltJoint = NULL;
- this->panJointNameP = new Param<std::string>("panJoint", "", 1);
- this->tiltJointNameP = new Param<std::string>("tiltJoint", "", 1);
- this->motionGainP = new Param<double>("motionGain",2,0);
- this->forceP = new Param<double>("force",10,0);
- this->commandTopicNameP = new Param<std::string>("commandTopicName","PTZ_cmd",0);
- this->stateTopicNameP = new Param<std::string>("stateTopicName","PTZ_state",0);
+ Param::Begin(&this->parameters);
+ this->panJointNameP = new ParamT<std::string>("panJoint", "", 1);
+ this->tiltJointNameP = new ParamT<std::string>("tiltJoint", "", 1);
+ this->motionGainP = new ParamT<double>("motionGain",2,0);
+ this->forceP = new ParamT<double>("force",10,0);
+ this->commandTopicNameP = new ParamT<std::string>("commandTopicName","PTZ_cmd",0);
+ this->stateTopicNameP = new ParamT<std::string>("stateTopicName","PTZ_state",0);
+ Param::End();
rosnode = ros::g_node; // comes from where?
int argc = 0;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|
|
From: <hsu...@us...> - 2008-09-10 00:04:44
|
Revision: 4127
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4127&view=rev
Author: hsujohnhsu
Date: 2008-09-10 00:04:54 +0000 (Wed, 10 Sep 2008)
Log Message:
-----------
add flag <alwaysOn> to allow continuous on operation for controllers in Gazebo w/o Iface connection.
Modified Paths:
--------------
pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
Modified: pkg/trunk/3rdparty/gazebo/gazebo_patch.diff
===================================================================
--- pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/3rdparty/gazebo/gazebo_patch.diff 2008-09-10 00:04:54 UTC (rev 4127)
@@ -904,6 +904,20 @@
private: friend class DestroyerT<World>;
private: friend class SingletonT<World>;
};
+Index: server/controllers/Controller.hh
+===================================================================
+--- server/controllers/Controller.hh (revision 7016)
++++ server/controllers/Controller.hh (working copy)
+@@ -105,6 +105,9 @@
+ /// \brief The entity that owns this controller
+ protected: Entity *parent;
+
++ /// \breif flag to keep controllers updating continuously
++ protected: ParamT<bool> *alwaysOnP;
++
+ /// \brief Update period
+ protected: double updatePeriod;
+ protected: ParamT<double> *updatePeriodP;
Index: server/controllers/camera/generic/Generic_Camera.cc
===================================================================
--- server/controllers/camera/generic/Generic_Camera.cc (revision 7016)
@@ -938,13 +952,33 @@
===================================================================
--- server/controllers/Controller.cc (revision 7016)
+++ server/controllers/Controller.cc (working copy)
-@@ -75,11 +75,15 @@
+@@ -43,6 +43,7 @@
+ {
+ Param::Begin(&this->parameters);
+ this->nameP = new ParamT<std::string>("name","",1);
++ this->alwaysOnP = new ParamT<bool>("alwaysOn", false, 0);
+ this->updatePeriodP = new ParamT<double>("updateRate", 10, 0);
+ Param::End();
+
+@@ -60,6 +61,7 @@
+ {
+ this->Fini();
+ delete this->nameP;
++ delete this->alwaysOnP;
+ delete this->updatePeriodP;
+ }
+
+@@ -75,10 +77,17 @@
this->typeName = node->GetName();
this->nameP->Load(node);
+
++ this->alwaysOnP->Load(node);
++
this->updatePeriodP->Load(node);
- this->updatePeriod = 1.0 / (this->updatePeriodP->GetValue() + 1e-6);
+
+- this->lastUpdate = -1e6;
+ double updateRate = this->updatePeriodP->GetValue();
+ if (updateRate == 0)
+ this->updatePeriod = 0.0; // no throttling if updateRate is 0
@@ -952,11 +986,17 @@
+ this->updatePeriod = 1.0 / updateRate;
+ this->lastUpdate = Simulator::Instance()->GetSimTime();
-- this->lastUpdate = -1e6;
--
childNode = node->GetChildByNSPrefix("interface");
- // Create the interfaces
+@@ -178,7 +187,7 @@
+ /// Update the controller. Called every cycle.
+ void Controller::Update()
+ {
+- if (this->IsConnected())
++ if (this->IsConnected() || this->alwaysOnP->GetValue())
+ {
+ if (lastUpdate + updatePeriod <= Simulator::Instance()->GetSimTime())
+ {
Index: server/controllers/ptz/generic/Generic_PTZ.cc
===================================================================
--- server/controllers/ptz/generic/Generic_PTZ.cc (revision 7016)
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -9,11 +9,12 @@
<!-- PR2_ACTARRAY -->
<controller:gazebo_actuators name="gazebo_actuators" plugin="libgazebo_actuators.so">
- <updateRate>100.0</updateRate>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
- <robot filename="pr2_gazebo_actuators.xml" />
+ <robot filename="pr2_gazebo_actuators.xml" />
- <interface:audio name="gazebo_actuators_dummy_iface" />
+ <interface:audio name="gazebo_actuators_dummy_iface" />
</controller:gazebo_actuators>
</verbatim>
@@ -25,6 +26,7 @@
<!-- ptz camera controls -->
<controller:generic_ptz name="ptz_cam_left_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
@@ -32,6 +34,7 @@
</controller:generic_ptz>
<controller:generic_ptz name="ptz_cam_right_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
@@ -40,27 +43,30 @@
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_right</bodyName>
- <topicName>gripper_roll_right_pose</topicName>
- <frameName>gripper_roll_right_frame</frameName>
- <interface:position name="p3d_right_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose</topicName>
+ <frameName>gripper_roll_right_frame</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_left</bodyName>
- <topicName>gripper_roll_left_pose</topicName>
- <frameName>gripper_roll_left_frame</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose</topicName>
+ <frameName>gripper_roll_left_frame</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose</topicName>
- <frameName>base_frame</frameName>
- <interface:position name="p3d_base_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose</topicName>
+ <frameName>base_frame</frameName>
+ <interface:position name="p3d_base_position"/>
</controller:P3D>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -10,15 +10,16 @@
<!-- PR2_ACTARRAY -->
<!-- uncomment for testing -->
<controller:test_actuators name="test_actuators" plugin="libtest_actuators.so">
- <updateRate>100.0</updateRate>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
- <!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
- <include>gazebo_joints.xml</include>
- <robot_filename>pr2_test_actuators.xml</robot_filename>
- <controller_filename>controllers.xml</controller_filename>
- <actuator_filename>actuators.xml</actuator_filename>
+ <!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
+ <include>gazebo_joints.xml</include>
+ <robot_filename>pr2_test_actuators.xml</robot_filename>
+ <controller_filename>controllers.xml</controller_filename>
+ <actuator_filename>actuators.xml</actuator_filename>
- <interface:audio name="test_actuators_dummy_iface" />
+ <interface:audio name="test_actuators_dummy_iface" />
</controller:test_actuators>
</verbatim>
@@ -30,6 +31,7 @@
<!-- ptz camera controls -->
<controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
@@ -39,6 +41,7 @@
</controller:Ros_PTZ>
<controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
@@ -49,27 +52,30 @@
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_right</bodyName>
- <topicName>gripper_roll_right_pose</topicName>
- <frameName>gripper_roll_right_frame</frameName>
- <interface:position name="p3d_right_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose</topicName>
+ <frameName>gripper_roll_right_frame</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_left</bodyName>
- <topicName>gripper_roll_left_pose</topicName>
- <frameName>gripper_roll_left_frame</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose</topicName>
+ <frameName>gripper_roll_left_frame</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose</topicName>
- <frameName>base_frame</frameName>
- <interface:position name="p3d_base_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose</topicName>
+ <frameName>base_frame</frameName>
+ <interface:position name="p3d_base_position"/>
</controller:P3D>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/controllers_gazebo_test_headless.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -10,6 +10,7 @@
<!-- PR2_ACTARRAY -->
<!-- uncomment for testing -->
<controller:test_actuators name="test_actuators" plugin="libtest_actuators.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
<!-- used exclusively by test_actuators to find out where these files are, in combination with env var MC_RESOURCE_PATH -->
@@ -30,6 +31,7 @@
<!-- ptz camera controls -->
<controller:Ros_PTZ name="ptz_cam_left_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_left_joint</panJoint>
<tiltJoint>ptz_tilt_left_joint</tiltJoint>
@@ -39,6 +41,7 @@
</controller:Ros_PTZ>
<controller:Ros_PTZ name="ptz_cam_right_controller" plugin="libRos_PTZ.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate> <!-- rate not implemented in gazebo yet-->
<panJoint>ptz_pan_right_joint</panJoint>
<tiltJoint>ptz_tilt_right_joint</tiltJoint>
@@ -49,27 +52,30 @@
<!-- P3D for position groundtruth -->
<controller:P3D name="p3d_right_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_right</bodyName>
- <topicName>gripper_roll_right_pose</topicName>
- <frameName>gripper_roll_right_frame</frameName>
- <interface:position name="p3d_right_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_right</bodyName>
+ <topicName>gripper_roll_right_pose</topicName>
+ <frameName>gripper_roll_right_frame</frameName>
+ <interface:position name="p3d_right_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_left_wrist_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>gripper_roll_left</bodyName>
- <topicName>gripper_roll_left_pose</topicName>
- <frameName>gripper_roll_left_frame</frameName>
- <interface:position name="p3d_left_wrist_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>gripper_roll_left</bodyName>
+ <topicName>gripper_roll_left_pose</topicName>
+ <frameName>gripper_roll_left_frame</frameName>
+ <interface:position name="p3d_left_wrist_position"/>
</controller:P3D>
<controller:P3D name="p3d_base_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>base</bodyName>
- <topicName>base_pose</topicName>
- <frameName>base_frame</frameName>
- <interface:position name="p3d_base_position"/>
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <bodyName>base</bodyName>
+ <topicName>base_pose</topicName>
+ <frameName>base_frame</frameName>
+ <interface:position name="p3d_base_position"/>
</controller:P3D>
Modified: pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-09-09 23:14:57 UTC (rev 4126)
+++ pkg/trunk/robot_descriptions/wg_robot_description/pr2/pr2.xml 2008-09-10 00:04:54 UTC (rev 4127)
@@ -1755,6 +1755,7 @@
<maxRange>10.0</maxRange>
<updateRate>10.0</updateRate>
<controller:ros_laser name="ros_tilt_laser_controller" plugin="libRos_Laser.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>tilt_scan</topicName>
<frameName>tilt_laser</frameName>
@@ -1816,6 +1817,7 @@
<maxRange>10.0</maxRange>
<updateRate>10.0</updateRate>
<controller:ros_laser name="ros_base_laser_controller" plugin="libRos_Laser.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<topicName>base_scan</topicName>
<frameName>base_laser</frameName>
@@ -1873,6 +1875,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="wrist_cam_left_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_wrist_left</topicName>
<frameName>wrist_camera_left</frameName>
@@ -1880,6 +1883,7 @@
</controller:ros_camera>
<!--
<controller:generic_camera name="wrist_cam_left_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<interface:camera name="wrist_cam_left_iface_1" />
</controller:generic_camera>
@@ -1936,6 +1940,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="wrist_cam_right_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_wrist_right</topicName>
<frameName>wrist_camera_right</frameName>
@@ -1943,6 +1948,7 @@
</controller:ros_camera>
<!--
<controller:generic_camera name="wrist_cam_right_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<interface:camera name="wrist_cam_right_iface_1" />
</controller:generic_camera>
@@ -1999,6 +2005,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="forearm_cam_left_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_forearm_left</topicName>
<frameName>forearm_roll_left</frameName>
@@ -2056,6 +2063,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="forearm_cam_right_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>image_forearm_right</topicName>
<frameName>forearm_roll_right</frameName>
@@ -2143,6 +2151,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="ptz_cam_left_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>PTZL_image</topicName>
<frameName>ptz_left</frameName>
@@ -2231,6 +2240,7 @@
<farClip>100</farClip>
<updateRate>15.0</updateRate>
<controller:ros_camera name="ptz_cam_right_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>PTZR_image</topicName>
<frameName>ptz_right</frameName>
@@ -2296,6 +2306,7 @@
<baseline>0.2</baseline>
<updateRate>15.0</updateRate>
<controller:stereocamera name="stereo_camera_controller">
+ <alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<interface:stereocamera name="stereo_iface_0" />
<interface:camera name="camera_iface_0" />
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|