|
From: <is...@us...> - 2008-07-18 19:14:13
|
Revision: 1773
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=1773&view=rev
Author: isucan
Date: 2008-07-18 19:14:17 +0000 (Fri, 18 Jul 2008)
Log Message:
-----------
renamed robot_model package to robot_mechanism_model and moved it to the robot_models directory (conflicting names with robot models for motion planning). The include path now is <mechanism_model/...> instead of <robot_model/...>. If code appears to be broken, just do make clean in the directory of the package that does not build
Modified Paths:
--------------
pkg/trunk/controllers/genericControllers/include/genericControllers/JointController.h
pkg/trunk/controllers/genericControllers/manifest.xml
pkg/trunk/controllers/pr2Controllers/include/pr2Controllers/BaseController.h
pkg/trunk/controllers/pr2Controllers/src/BaseController.cpp
pkg/trunk/controllers/rosControllers/manifest.xml
pkg/trunk/controllers/testControllers/manifest.xml
pkg/trunk/controllers/testControllers/src/test_base.cpp
pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h
pkg/trunk/drivers/robot/pr2/libpr2HW/manifest.xml
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/base_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/robot/pr2_gazebo/src/test2.cpp
pkg/trunk/simulators/rosgazebo/include/RosGazeboNode/RosGazeboNode.h
pkg/trunk/simulators/rosgazebo/manifest.xml
pkg/trunk/simulators/rosgazebo/src/rosgazebo.cc
Added Paths:
-----------
pkg/trunk/robot_models/robot_mechanism_model/
pkg/trunk/robot_models/robot_mechanism_model/CMakeLists.txt
pkg/trunk/robot_models/robot_mechanism_model/Makefile
pkg/trunk/robot_models/robot_mechanism_model/include/
pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/
pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/joint.h
pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/link.h
pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/robot.h
pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/transmission.h
pkg/trunk/robot_models/robot_mechanism_model/manifest.xml
pkg/trunk/robot_models/robot_mechanism_model/src/
pkg/trunk/robot_models/robot_mechanism_model/src/CoupledTransmission.cpp
pkg/trunk/robot_models/robot_mechanism_model/src/SimpleTransmission.cpp
Removed Paths:
-------------
pkg/trunk/mechanism/robot_model/
Modified: pkg/trunk/controllers/genericControllers/include/genericControllers/JointController.h
===================================================================
--- pkg/trunk/controllers/genericControllers/include/genericControllers/JointController.h 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/genericControllers/include/genericControllers/JointController.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -74,7 +74,7 @@
#include <genericControllers/Controller.h>
#include <genericControllers/Pid.h>
#include <math_utils/angles.h>
-#include <robot_model/joint.h>
+#include <mechanism_model/joint.h>
#include <string>
using namespace mechanism;
Modified: pkg/trunk/controllers/genericControllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/genericControllers/manifest.xml 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/genericControllers/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -6,7 +6,7 @@
<license>BSD</license>
<depend package="pr2Core" />
<depend package="math_utils" />
- <depend package="robot_model" />
+ <depend package="robot_mechanism_model" />
<url>http://pr.willowgarage.com</url>
<repository>http://pr.willowgarage.com/repos</repository>
<export>
Modified: pkg/trunk/controllers/pr2Controllers/include/pr2Controllers/BaseController.h
===================================================================
--- pkg/trunk/controllers/pr2Controllers/include/pr2Controllers/BaseController.h 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/pr2Controllers/include/pr2Controllers/BaseController.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -23,8 +23,8 @@
#include <genericControllers/Controller.h>
#include <genericControllers/JointController.h>
-#include <robot_model/joint.h>
-#include <robot_model/robot.h>
+#include <mechanism_model/joint.h>
+#include <mechanism_model/robot.h>
using namespace std;
Modified: pkg/trunk/controllers/pr2Controllers/src/BaseController.cpp
===================================================================
--- pkg/trunk/controllers/pr2Controllers/src/BaseController.cpp 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/pr2Controllers/src/BaseController.cpp 2008-07-18 19:14:17 UTC (rev 1773)
@@ -6,7 +6,7 @@
#include <sys/time.h>
-#include <robot_model/joint.h>
+#include <mechanism_model/joint.h>
#define BASE_NUM_JOINTS 12
Modified: pkg/trunk/controllers/rosControllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/rosControllers/manifest.xml 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/rosControllers/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -12,7 +12,7 @@
<depend package="math_utils" />
<depend package="string_utils" />
<depend package="libKDL" />
- <depend package="robot_model" />
+ <depend package="robot_mechanism_model" />
<export>
<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lRosJointController"/>
</export>
Modified: pkg/trunk/controllers/testControllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/testControllers/manifest.xml 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/testControllers/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -7,7 +7,7 @@
<depend package="pr2Controllers" />
<depend package="genericControllers" />
<depend package="hw_interface" />
- <depend package="robot_model" />
+ <depend package="robot_mechanism_model" />
<url>http://pr.willowgarage.com</url>
<repository>http://pr.willowgarage.com/repos</repository>
<export>
Modified: pkg/trunk/controllers/testControllers/src/test_base.cpp
===================================================================
--- pkg/trunk/controllers/testControllers/src/test_base.cpp 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/controllers/testControllers/src/test_base.cpp 2008-07-18 19:14:17 UTC (rev 1773)
@@ -2,7 +2,7 @@
#include <hw_interface/hardware_interface.h>
#include <pr2Controllers/BaseController.h>
#include <genericControllers/JointController.h>
-#include <robot_model/joint.h>
+#include <mechanism_model/joint.h>
#include <sys/time.h>
#include <signal.h>
Modified: pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/drivers/robot/pr2/libpr2HW/include/libpr2HW/pr2HW.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -43,7 +43,7 @@
#include <string>
#include <list>
#include <vector>
-#include <robot_model/joint.h>
+#include <mechanism_model/joint.h>
namespace PR2
{
Modified: pkg/trunk/drivers/robot/pr2/libpr2HW/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/libpr2HW/manifest.xml 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/drivers/robot/pr2/libpr2HW/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -11,7 +11,7 @@
<depend package="gazebo"/>
<depend package="pr2Core"/>
<depend package="libKinematics"/>
-<depend package="robot_model"/>
+<depend package="robot_mechanism_model"/>
<export>
<cpp cflags="-I${prefix}/include" lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lpr2HW"/>
</export>
Modified: pkg/trunk/mechanism/mechanism_control/include/mechanism_control/base_control.h
===================================================================
--- pkg/trunk/mechanism/mechanism_control/include/mechanism_control/base_control.h 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/mechanism/mechanism_control/include/mechanism_control/base_control.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -28,7 +28,7 @@
#ifndef MECHANISM_CONTROL_H
#define MECHANISM_CONTROL_H
-#include <robot_model/robot.h>
+#include <mechanism_model/robot.h>
#include <rosthread/mutex.h>
#include <map>
#include <pr2Controllers/BaseController.h>
Modified: pkg/trunk/mechanism/mechanism_control/manifest.xml
===================================================================
--- pkg/trunk/mechanism/mechanism_control/manifest.xml 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/mechanism/mechanism_control/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -8,7 +8,7 @@
<depend package="rosthread"/>
<depend package="std_msgs"/>
<depend package="hw_interface"/>
-<depend package="robot_model"/>
+<depend package="robot_mechanism_model"/>
<depend package="pr2Controllers"/>
<depend package="etherdrive_hardware"/>
Modified: pkg/trunk/robot/pr2_gazebo/src/test2.cpp
===================================================================
--- pkg/trunk/robot/pr2_gazebo/src/test2.cpp 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/robot/pr2_gazebo/src/test2.cpp 2008-07-18 19:14:17 UTC (rev 1773)
@@ -25,7 +25,7 @@
// robot model
#include <pr2Core/pr2Core.h>
-#include <robot_model/joint.h>
+#include <mechanism_model/joint.h>
// gazebo hardware, sensors
#include <gazebo_hardware/gazebo_hardware.h>
Added: pkg/trunk/robot_models/robot_mechanism_model/CMakeLists.txt
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/CMakeLists.txt (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/CMakeLists.txt 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,4 @@
+cmake_minimum_required(VERSION 2.6)
+include(rosbuild)
+rospack(robot_mechanism_model)
+rospack_add_library(mechanism_model src/SimpleTransmission.cpp)
Added: pkg/trunk/robot_models/robot_mechanism_model/Makefile
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/Makefile (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/Makefile 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1 @@
+include $(shell rospack find mk)/cmake.mk
Added: pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/joint.h
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/joint.h (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/joint.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,57 @@
+
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2008, Eric Berger
+//
+// 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 Stanford University 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 JOINT_H
+#define JOINT_H
+
+namespace mechanism {
+ class Joint{
+ public:
+
+ void enforceLimits();
+
+ char *name;
+ int type;
+
+ //Update every cycle from input data
+ bool initialized;
+ double position;
+ double velocity;
+ double appliedEffort;
+
+ //Written every cycle out to motor boards
+ double commandedEffort;
+
+ //Never changes
+ double jointLimitMin;
+ double jointLimitMax;
+ double effortLimit;
+ double velocityLimit;
+ };
+}
+
+#endif
Added: pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/link.h
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/link.h (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/link.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,41 @@
+
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2008, Eric Berger
+//
+// 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 Stanford University 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 LINK_H
+#define LINK_H
+
+#include "mechanism_model/joint.h"
+
+namespace mechanism {
+ class Link{
+ char *name;
+ //Pointer to KDL link
+ Joint *joint;
+ };
+}
+
+#endif
Added: pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/robot.h
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/robot.h (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/robot.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,53 @@
+
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2008, Eric Berger
+//
+// 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 Stanford University 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.
+//////////////////////////////////////////////////////////////////////////////
+
+//The robot model is populated by the control code infrastructure and used by all the controllers to read mechanism state and command mechanism motion.
+
+#ifndef ROBOT_H
+#define ROBOT_H
+
+#include "mechanism_model/link.h"
+#include "mechanism_model/joint.h"
+#include "mechanism_model/transmission.h"
+
+namespace mechanism {
+ class Robot{
+ public:
+ Robot(char *ns){};
+ ~Robot(){};
+ char *name;
+ Link *link;
+ int numLinks;
+ Joint *joint;
+ int numJoints;
+ SimpleTransmission *transmission;
+ int numTransmissions;
+ };
+}
+
+#endif
Added: pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/transmission.h
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/transmission.h (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/include/mechanism_model/transmission.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,99 @@
+
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2008, Eric Berger
+//
+// 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 Stanford University 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 TRANSMISSION_H
+#define TRANSMISSION_H
+
+#include "mechanism_model/joint.h"
+#include "hw_interface/hardware_interface.h"
+
+namespace mechanism {
+
+ /* class Transmission{
+
+ public:
+
+ Transmission(){};
+
+ virtual ~Transmission(){};
+
+ virtual void propagatePosition(); //Use encoder data to fill out joint position and velocities
+
+ virtual void propagateEffort(); //Use commanded joint efforts to fill out commanded motor currents
+
+ };
+ */
+ class SimpleTransmission{
+
+ public:
+
+ SimpleTransmission(Joint *joint, Actuator *actuator, double mechanicalReduction, double motorTorqueConstant, double ticksPerRadian);
+
+ SimpleTransmission(){};
+
+ ~SimpleTransmission(){};
+
+ Actuator *actuator;
+
+ Joint *joint;
+
+ double mechanicalReduction;
+
+ double motorTorqueConstant;
+
+ double pulsesPerRevolution;
+
+ void propagatePosition();
+
+ void propagateEffort();
+ };
+ /*
+ class CoupledTransmission : public Transmission{
+
+ public:
+
+ void CoupledTranmission(Actuator *actuator, Joint *joint, double mechanicalReduction, double motorTorqueConstant);
+
+ };
+
+ class NonlinearTransmission : public Transmission{
+
+ public:
+
+ NonlinearTransmission(Actuator *actuator, Joint *joint, double mechanicalReduction, double motorTorqueConstant);
+
+ Actuator *actuator;
+
+ Joint *joint;
+
+ // ?? Lookup table
+ };
+ */
+}
+
+#endif
Added: pkg/trunk/robot_models/robot_mechanism_model/manifest.xml
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/manifest.xml (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,11 @@
+<package>
+<description brief="Mechanism model">
+</description>
+<author>Eric Berger be...@wi...</author>
+<license>BSD</license>
+<depend package='hw_interface'/>
+<url>http://pr.willowgarage.com</url>
+<export>
+ <cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lmechanism_model -Wl,-rpath,${prefix}/lib"/>
+</export>
+</package>
Added: pkg/trunk/robot_models/robot_mechanism_model/src/CoupledTransmission.cpp
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/src/CoupledTransmission.cpp (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/src/CoupledTransmission.cpp 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,46 @@
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2008, Sachin Chitta, Jimmy Sastra
+//
+// 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 Stanford University 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.
+//////////////////////////////////////////////////////////////////////////////
+
+// Simple transmission implementation
+#include <mechanism/transmission.h>
+
+CoupledTransmission(Actuator *actuator, Joint *joint, double mechanicalReduction, double motorTorqueConstant){
+ this->actuator = actuator;
+ this->joint = joint;
+ this->mechanicalReduction = mechanicalReduction;
+ this->motorTorqueConstant = motorTorqueConstant;
+ this->ticksPerRadian = ticksPerRadian;
+}
+
+void CoupledTransmission::propagatePosition(){
+ this->joint.position = this->ticksPerRadian * this->actuator.state.encoderCount;
+ this->joint.appliedEffort = this->actuator.lastMeasuredCurrent * (motorTorqueConstant * mechanicalReduction);
+}
+
+void CoupledTransmission::propagateEffort(){
+ this->actuator.command.current = this->joint.commandedEffort/(motorTorqueConstant * mechanicalReduction);
+}
Added: pkg/trunk/robot_models/robot_mechanism_model/src/SimpleTransmission.cpp
===================================================================
--- pkg/trunk/robot_models/robot_mechanism_model/src/SimpleTransmission.cpp (rev 0)
+++ pkg/trunk/robot_models/robot_mechanism_model/src/SimpleTransmission.cpp 2008-07-18 19:14:17 UTC (rev 1773)
@@ -0,0 +1,57 @@
+///////////////////////////////////////////////////////////////////////////////
+// Copyright (C) 2008, Sachin Chitta, Jimmy Sastra
+//
+// 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 Stanford University 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.
+//////////////////////////////////////////////////////////////////////////////
+
+// Simple transmission implementation
+#include <mechanism_model/transmission.h>
+#include <mechanism_model/joint.h>
+#include <math.h>
+#include <stdio.h>
+
+using namespace mechanism;
+
+SimpleTransmission::SimpleTransmission(Joint *joint, Actuator *actuator, double mechanicalReduction, double motorTorqueConstant, double pulsesPerRevolution)
+{
+ this->joint = joint;
+ this->actuator = actuator;
+ this->mechanicalReduction = mechanicalReduction;
+ this->motorTorqueConstant = motorTorqueConstant;
+ this->pulsesPerRevolution = pulsesPerRevolution;
+}
+
+
+void SimpleTransmission::propagatePosition(){
+ this->joint->position = ((double)this->actuator->state.encoderCount*2*M_PI)/(pulsesPerRevolution * mechanicalReduction);
+ this->joint->velocity = ((double)this->actuator->state.encoderVelocity*2*M_PI)/(pulsesPerRevolution * mechanicalReduction);
+ this->joint->appliedEffort = this->actuator->state.lastMeasuredCurrent * (motorTorqueConstant * mechanicalReduction);
+}
+
+void SimpleTransmission::propagateEffort(){
+ this->actuator->command.current = this->joint->commandedEffort/(motorTorqueConstant * mechanicalReduction);
+#ifdef DEBUG
+ printf("Transmission:: %f , %f\n",this->joint->commandedEffort, this->actuator->command.current);
+#endif
+}
Modified: pkg/trunk/simulators/rosgazebo/include/RosGazeboNode/RosGazeboNode.h
===================================================================
--- pkg/trunk/simulators/rosgazebo/include/RosGazeboNode/RosGazeboNode.h 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/simulators/rosgazebo/include/RosGazeboNode/RosGazeboNode.h 2008-07-18 19:14:17 UTC (rev 1773)
@@ -35,7 +35,7 @@
#include <pr2Controllers/GripperController.h>
#include "ringbuffer.h"
-#include "robot_model/joint.h"
+#include "mechanism_model/joint.h"
// roscpp
#include <ros/node.h>
// roscpp - laser
Modified: pkg/trunk/simulators/rosgazebo/manifest.xml
===================================================================
--- pkg/trunk/simulators/rosgazebo/manifest.xml 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/simulators/rosgazebo/manifest.xml 2008-07-18 19:14:17 UTC (rev 1773)
@@ -15,7 +15,7 @@
<depend package="math_utils" />
<depend package="string_utils" />
<depend package="libKDL" />
- <depend package="robot_model" />
+ <depend package="robot_mechanism_model" />
<depend package="hw_interface" />
<depend package="gazebo_hardware" />
<depend package="gazebo_sensors" />
Modified: pkg/trunk/simulators/rosgazebo/src/rosgazebo.cc
===================================================================
--- pkg/trunk/simulators/rosgazebo/src/rosgazebo.cc 2008-07-18 18:55:15 UTC (rev 1772)
+++ pkg/trunk/simulators/rosgazebo/src/rosgazebo.cc 2008-07-18 19:14:17 UTC (rev 1773)
@@ -23,7 +23,7 @@
#include <pthread.h>
#include <pr2Core/pr2Core.h>
-#include <robot_model/joint.h>
+#include <mechanism_model/joint.h>
// gazebo
#include <libpr2API/pr2API.h>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|