|
From: <stu...@us...> - 2008-09-18 16:50:37
|
Revision: 4455
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4455&view=rev
Author: stuglaser
Date: 2008-09-18 23:50:44 +0000 (Thu, 18 Sep 2008)
Log Message:
-----------
Moved generic_controllers to robot_mechanism_controllers
Added Paths:
-----------
pkg/trunk/controllers/robot_mechanism_controllers/
pkg/trunk/controllers/robot_mechanism_controllers/CMakeLists.txt
pkg/trunk/controllers/robot_mechanism_controllers/Makefile
pkg/trunk/controllers/robot_mechanism_controllers/doc.h
pkg/trunk/controllers/robot_mechanism_controllers/include/
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_effort_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_autotuner.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_blind_calibration_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_calibration_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_manual_calibration_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_pd_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/ramp_effort_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/sine_sweep_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
pkg/trunk/controllers/robot_mechanism_controllers/msg/
pkg/trunk/controllers/robot_mechanism_controllers/msg/SingleJointPosCmd.msg
pkg/trunk/controllers/robot_mechanism_controllers/scripts/
pkg/trunk/controllers/robot_mechanism_controllers/scripts/control.py
pkg/trunk/controllers/robot_mechanism_controllers/src/
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_effort_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_autotuner.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_blind_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_effort_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_manual_calibration_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_pd_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/ramp_effort_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/robot_mechanism_controllers/
pkg/trunk/controllers/robot_mechanism_controllers/src/robot_mechanism_controllers/__init__.py
pkg/trunk/controllers/robot_mechanism_controllers/src/robot_mechanism_controllers/controller.py
pkg/trunk/controllers/robot_mechanism_controllers/src/robot_mechanism_controllers/controllers.py
pkg/trunk/controllers/robot_mechanism_controllers/src/robot_mechanism_controllers/joint_controllers.py
pkg/trunk/controllers/robot_mechanism_controllers/src/robot_mechanism_controllers/joint_velocity_controller.py
pkg/trunk/controllers/robot_mechanism_controllers/src/sine_sweep_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/srv/
pkg/trunk/controllers/robot_mechanism_controllers/srv/BeginJointSineSweep.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/CalibrateJoint.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/GetActual.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/GetCommand.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/GetPDActual.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/GetPDCommand.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/GetPosition.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/SetCommand.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/SetPDCommand.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/SetPosition.srv
pkg/trunk/controllers/robot_mechanism_controllers/srv/SetVectorCommand.srv
pkg/trunk/mechanism/mechanism_model/include/mechanism_model/controller.h
Removed Paths:
-------------
pkg/trunk/controllers/generic_controllers/CMakeLists.txt
pkg/trunk/controllers/generic_controllers/Makefile
pkg/trunk/controllers/generic_controllers/doc.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/cartesian_effort_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_autotuner.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_blind_calibration_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_calibration_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_effort_controller.h
pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_manual_calibration_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/manifest.xml
pkg/trunk/controllers/generic_controllers/msg/SingleJointPosCmd.msg
pkg/trunk/controllers/generic_controllers/scripts/control.py
pkg/trunk/controllers/generic_controllers/src/cartesian_effort_controller.cpp
pkg/trunk/controllers/generic_controllers/src/generic_controllers/controller.py
pkg/trunk/controllers/generic_controllers/src/generic_controllers/controllers.py
pkg/trunk/controllers/generic_controllers/src/generic_controllers/joint_controllers.py
pkg/trunk/controllers/generic_controllers/src/generic_controllers/joint_velocity_controller.py
pkg/trunk/controllers/generic_controllers/src/joint_autotuner.cpp
pkg/trunk/controllers/generic_controllers/src/joint_blind_calibration_controller.cpp
pkg/trunk/controllers/generic_controllers/src/joint_calibration_controller.cpp
pkg/trunk/controllers/generic_controllers/src/joint_effort_controller.cpp
pkg/trunk/controllers/generic_controllers/src/joint_manual_calibration_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/generic_controllers/srv/BeginJointSineSweep.srv
pkg/trunk/controllers/generic_controllers/srv/CalibrateJoint.srv
pkg/trunk/controllers/generic_controllers/srv/GetActual.srv
pkg/trunk/controllers/generic_controllers/srv/GetCommand.srv
pkg/trunk/controllers/generic_controllers/srv/GetPDActual.srv
pkg/trunk/controllers/generic_controllers/srv/GetPDCommand.srv
pkg/trunk/controllers/generic_controllers/srv/GetPosition.srv
pkg/trunk/controllers/generic_controllers/srv/SetCommand.srv
pkg/trunk/controllers/generic_controllers/srv/SetPDCommand.srv
pkg/trunk/controllers/generic_controllers/srv/SetPosition.srv
pkg/trunk/controllers/generic_controllers/srv/SetVectorCommand.srv
Deleted: pkg/trunk/controllers/generic_controllers/CMakeLists.txt
===================================================================
--- pkg/trunk/controllers/generic_controllers/CMakeLists.txt 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/CMakeLists.txt 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,17 +0,0 @@
-cmake_minimum_required(VERSION 2.6)
-include(rosbuild)
-rospack(generic_controllers)
-genmsg()
-gensrv()
-rospack_add_library(generic_controllers
- src/joint_effort_controller.cpp
- src/joint_position_controller.cpp
- src/joint_velocity_controller.cpp
- src/cartesian_effort_controller.cpp
- src/ramp_effort_controller.cpp
- src/sine_sweep_controller.cpp
- src/joint_autotuner.cpp
- src/joint_pd_controller.cpp
- src/joint_calibration_controller.cpp
- src/joint_blind_calibration_controller.cpp
- src/joint_manual_calibration_controller.cpp)
Deleted: pkg/trunk/controllers/generic_controllers/Makefile
===================================================================
--- pkg/trunk/controllers/generic_controllers/Makefile 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/Makefile 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1 +0,0 @@
-include $(shell rospack find mk)/cmake.mk
Deleted: pkg/trunk/controllers/generic_controllers/doc.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/doc.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/doc.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,14 +0,0 @@
-/**
-@mainpage
-@htmlinclude manifest.html
-
-test
-
-Here are the controllers which are currently implemented:
- \li \ref controller::Pid "Pid"
- \li \ref controller::JointEffortController "Joint Effort Controller"
- \li \ref controller::JointPositionController "Joint Position Controller"
- \li \ref controller::JointVelocityController "Joint Velocity Controller"
- \li \ref controller::RampInputController "Ramp Input Controller"
- \li \ref controller::SineSweepController "Sine Sweep Controller"
-**/
Deleted: pkg/trunk/controllers/generic_controllers/include/generic_controllers/cartesian_effort_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/cartesian_effort_controller.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/cartesian_effort_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,87 +0,0 @@
-/*
- * 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.
- */
-
-/*
- * Example config:
-
- <controller type="CartesianEffortController" name="controller_name">
- <chain root="root_link" tip="tip_link" />
- </controller>
-
- * The root is fixed, and all commands are specified in its coordinate
- * frame.
- *
- * Author: Stuart Glaser
- */
-#ifndef CARTESIAN_EFFORT_CONTROLLER_H
-#define CARTESIAN_EFFORT_CONTROLLER_H
-
-#include <vector>
-#include "ros/node.h"
-#include "generic_controllers/SetVectorCommand.h"
-#include "generic_controllers/controller.h"
-#include "LinearMath/btVector3.h"
-
-namespace controller {
-
-class CartesianEffortController : public Controller
-{
-public:
- CartesianEffortController();
- ~CartesianEffortController();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- void update();
-
- btVector3 command_;
-
-private:
- std::vector<mechanism::LinkState*> links_; // root to tip
- std::vector<mechanism::JointState*> joints_; // root to tip, 1 element smaller than links_
-};
-
-class CartesianEffortControllerNode : public Controller
-{
-public:
- CartesianEffortControllerNode();
- ~CartesianEffortControllerNode();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- void update();
-
- bool setCommand(generic_controllers::SetVectorCommand::request &req,
- generic_controllers::SetVectorCommand::response &resp);
-
-private:
- CartesianEffortController c_;
-};
-
-}
-
-#endif
Deleted: pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,94 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-#pragma once
-/***************************************************/
-/*! \namespace controller
- \brief The controller namespace
-
- \class controller::Controller
- \brief A base level controller class.
-
- */
-/***************************************************/
-
-#include <misc_utils/factory.h>
-#include <mechanism_model/robot.h>
-
-#include <tinyxml/tinyxml.h>
-
-namespace controller
-{
-
- /*! \struct
- \brief This class holds information for a joint control parameter structure.
- */
- typedef struct
- {
- double p_gain; /** P gain */
-
- double i_gain; /** I gain */
-
- double d_gain; /** D gain */
-
- double windup; /** windup protection value */
-
- std::string joint_name; /** joint name */
-
- std::string control_type; /** control type */
-
- }JointControlParam;
-
-
-class Controller;
-typedef misc_utils::Factory<Controller> ControllerFactory;
-
-#define ROS_REGISTER_CONTROLLER(c) \
- controller::Controller *ROS_New_##c() { return new c(); } \
- bool ROS_CONTROLLER_##c = \
- controller::ControllerFactory::instance().registerType(#c, ROS_New_##c);
-
-class Controller
-{
-public:
- Controller()
- {
- }
- virtual ~Controller()
- {
- }
- virtual void update(void) = 0;
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config) = 0;
-};
-
-}
Deleted: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_autotuner.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_autotuner.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_autotuner.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,195 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointAutotuner
- \brief Joint Position Controller
-
- This class closes the loop around positon using
- a pid loop.
-
-*/
-/***************************************************/
-
-#include <ros/node.h>
-#include <vector>
-#include <generic_controllers/controller.h>
-#include <mechanism_model/pid.h>
-
-// Services
-#include <generic_controllers/SetCommand.h>
-#include <generic_controllers/GetActual.h>
-
-namespace controller
-{
-
-class JointAutotuner : public Controller
-{
- enum AutoControlState
- {
- START,POSITIVE_PEAK,NEGATIVE_PEAK, DONE, MANUAL
- };
-public:
- /*!
- * \brief Default Constructor of the JointAutotuner class.
- *
- */
- JointAutotuner();
-
- /*!
- * \brief Destructor of the JointAutotuner class.
- */
- ~JointAutotuner();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- * \param p_gain Proportional gain.
- * \param i_gain Integral gain.
- * \param d_gain Derivative gain.
- * \param windup Intergral limit.
- * \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,mechanism::Robot *robot, mechanism::Joint *joint);
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /*!
- * \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
- *
- * \param command
- */
- void setCommand(double command);
-
- /*!
- * \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
- */
- double getCommand();
-
- /*!
- * \brief Read the torque of the motor
- */
- double getMeasuredState();
-
- /*!
- * \brief Get latest time..
- */
- double getTime();
-
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
-
- virtual void update();
-
- double p_gain_;
- double i_gain_;
- double d_gain_;
-
- AutoControlState current_state_;
-
-private:
- bool tune_velocity_; /**<If true, uses velocity to tune. Otherwise uses position>*/
- mechanism::Joint* joint_; /**< Joint we're controlling.> */
- mechanism::JointState* joint_state_; /**< Joint we're controlling.> */
- Pid pid_controller_; /**< Internal PID controller.> */
- double last_time_; /**< Last time stamp of update.> */
- double command_; /**< Last commanded position.> */
- mechanism::Robot *robot_; /**< Pointer to robot structure.> */
- mechanism::RobotState *robot_state_; /**< Pointer to robot structure.> */
- const char* file_path_; /**<Filename and location to write results. >*/
- void writeGainValues(double period, double amplitude, double relay_height); /**<Calculate and write gain values> */
-
- double amplitude_; /**< Current amplitude of relay cycle> */
- double last_amplitude_;/**< Last amplitude of relay cycle> */
- double period_;/**< Current period of relay cycle> */
- double last_period_;/**< Last period of relay cycle> */
-
- double positive_peak_;/**< Positive peak reached in cycle> */
- double negative_peak_;/**< Negative peak reached in cycle> */
-
- double relay_height_;/**< Amount of relay input> */
- int successful_cycles_;/**< Number of matching cycles > */
- double crossing_point_;/**< Location of crossover point for relay test> */
- double cycle_start_time_;/**< Mark time of cycle start> */
-
- int num_cycles_; /*!<Number of cycles that need to match for autotuner to read as stable>!*/
- double amplitude_tolerance_; /*!<% variation amplitude allowed between successful cycles>!*/
- double period_tolerance_; /*!<% variation period allowed between successful cycles>!*/
- double relay_effort_percent_; /*!<% of effort limit to use in relay test>!*/
-
-};
-
-/***************************************************/
-/*! \class controller::JointAutotunerNode
- \brief Joint Position Controller ROS Node
-
- This class performs an autotuning routine using the relay method.
-
-
-*/
-/***************************************************/
-
-class JointAutotunerNode : public Controller
-{
-public:
- /*!
- * \brief Default Constructor
- *
- */
- JointAutotunerNode();
-
- /*!
- * \brief Destructor
- */
- ~JointAutotunerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- // Services
- bool setCommand(generic_controllers::SetCommand::request &req,
- generic_controllers::SetCommand::response &resp);
-
- bool getActual(generic_controllers::GetActual::request &req,
- generic_controllers::GetActual::response &resp);
-
-private:
- JointAutotuner *c_;
-};
-}
-
Deleted: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_blind_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_blind_calibration_controller.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_blind_calibration_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,135 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointCalibratonController
- \brief Joint Controller that finds zerop point
- \author Timothy Hunter <tjh...@wi...>
-
-
- This class moves the joint and reads the value of the clibration_reading_ field to find the zero position of the joint. Once these are determined, these values
- * are passed to the joint and enable the joint for the other controllers.
-
-*/
-/***************************************************/
-
-
-#include "joint_manual_calibration_controller.h"
-
-// Services
-#include <generic_controllers/CalibrateJoint.h>
-
-
-namespace controller
-{
-
-class JointBlindCalibrationController : public JointManualCalibrationController
-{
-public:
- /*!
- * \brief Default Constructor.
- *
- */
- JointBlindCalibrationController();
-
- /*!
- * \brief Destructor.
- */
- virtual ~JointBlindCalibrationController();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- *
- */
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
- virtual void update();
-
-protected:
-
- enum {SearchUp=100,SearchDown,SearchingUp,SearchingDown};
-
- double search_velocity_;
-
- double velocity_cmd_;
-
- double init_time;
-
- controller::JointVelocityController vcontroller_; /** The joint velocity controller used to sweep the joint.*/
-};
-
-
-/***************************************************/
-/*! \class controller::JointBlindCalibrationControllerNode
- \brief Joint Limit Controller ROS Node
-
- This class starts and stops the initialization sequence
-
-*/
-/***************************************************/
-
-class JointBlindCalibrationControllerNode : public Controller
-{
-public:
- /*!
- * \brief Default Constructor
- *
- */
- JointBlindCalibrationControllerNode();
-
- /*!
- * \brief Destructor
- */
- ~JointBlindCalibrationControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- // Services
- bool calibrateCommand(generic_controllers::CalibrateJoint::request &req,
- generic_controllers::CalibrateJoint::response &resp);
-
-private:
- JointBlindCalibrationController *c_;
-};
-}
-
-
Deleted: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_calibration_controller.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_calibration_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,134 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointCalibratonController
- \brief Joint Controller that finds zerop point
- \author Timothy Hunter <tjh...@wi...>
-
-
- This class moves the joint and reads the value of the clibration_reading_ field to find the zero position of the joint. Once these are determined, these values
- * are passed to the joint and enable the joint for the other controllers.
-
-*/
-/***************************************************/
-
-
-#include "joint_manual_calibration_controller.h"
-
-// Services
-#include <generic_controllers/CalibrateJoint.h>
-
-
-namespace controller
-{
-
-class JointCalibrationController : public JointManualCalibrationController
-{
-public:
- /*!
- * \brief Default Constructor.
- *
- */
- JointCalibrationController();
-
- /*!
- * \brief Destructor.
- */
- virtual ~JointCalibrationController();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- *
- */
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
- virtual void update();
-
-protected:
-
- double previous_reading_; /**Previous calibration reading*/
-
- double search_velocity_;
-
- double velocity_cmd_;
-
- controller::JointVelocityController vcontroller_; /** The joint velocity controller used to sweep the joint.*/
-};
-
-
-/** @class controller::JointControllerCalibrationNode
- * @\brief ROS interface for a joint calibration controller
- * This class is a wrapper around the calibrateCmd service call and it should be its only use
- */
-class JointCalibrationControllerNode : public Controller
-{
-public:
- /*!
- * \brief Default Constructor
- *
- */
- JointCalibrationControllerNode();
-
- /*!
- * \brief Destructor
- */
- ~JointCalibrationControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /** \brief initializes the calibration procedure (blocking service)
- * This service starts the calibration sequence of the joint and waits to return until the calibration sequence is finished.
- *
- * @param req
- * @param resp
- * @return
- */
- bool calibrateCommand(generic_controllers::CalibrateJoint::request &req,
- generic_controllers::CalibrateJoint::response &resp);
-
-private:
- JointCalibrationController *c_;
-};
-}
-
-
Deleted: 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-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_effort_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,156 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointEffortController
- \brief Joint Torque Controller
-
- This class basically passes the commanded effort
- down through the transmissions and safety code.
-
- <controller type="JointEffortController" name="controller_name">
- <joint name="joint_to_control" />
- </controller>
-
-*/
-/***************************************************/
-
-
-#include <ros/node.h>
-#include <generic_controllers/controller.h>
-
-// Services
-#include <generic_controllers/SetCommand.h>
-#include <generic_controllers/GetActual.h>
-
-namespace controller
-{
-
-class JointEffortController : public Controller
-{
-public:
- /*!
- * \brief Default Constructor of the JointEffortController class.
- *
- */
- JointEffortController();
-
- /*!
- * \brief Destructor of the JointEffortController class.
- */
- ~JointEffortController();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- *
- */
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /*!
- * \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
- *
- * \param command
- */
- void setCommand(double command);
-
- /*!
- * \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
- */
- double getCommand();
-
- /*!
- * \brief Read the effort of the joint
- */
- double getMeasuredEffort();
-
- /*!
- * \brief Get latest time..
- */
- double getTime();
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
-
- virtual void update();
-
-private:
- mechanism::JointState *joint_; /**< Joint we're controlling. */
- mechanism::RobotState *robot_; /**< Pointer to robot structure. */
- double command_; /**< Last commanded position. */
-};
-
-/***************************************************/
-/*! \class controller::JointEffortControllerNode
- \brief Joint Torque Controller ROS Node
-
- This class basically passes the commanded effort
- down through the transmissions and safety code.
-
-*/
-/***************************************************/
-
-class JointEffortControllerNode : public Controller
-{
-public:
- /*!
- * \brief Default Constructor
- *
- */
- JointEffortControllerNode();
-
- /*!
- * \brief Destructor
- */
- ~JointEffortControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- // Services
- bool setCommand(generic_controllers::SetCommand::request &req,
- generic_controllers::SetCommand::response &resp);
-
- bool getActual(generic_controllers::GetActual::request &req,
- generic_controllers::GetActual::response &resp);
-
-private:
- JointEffortController *c_;
-};
-}
-
-
Deleted: pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_manual_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_manual_calibration_controller.h 2008-09-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_manual_calibration_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,168 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointCalibratonController
- \brief Joint Controller that finds zerop point
- \author Timothy Hunter <tjh...@wi...>
-
-
- This class moves the joint and reads the value of the clibration_reading_ field to find the zero position of the joint. Once these are determined, these values
- * are passed to the joint and enable the joint for the other controllers.
-
- */
-/***************************************************/
-
-
-#include <ros/node.h>
-#include <generic_controllers/controller.h>
-#include <generic_controllers/joint_velocity_controller.h>
-#include <mechanism_model/robot.h>
-#include <hardware_interface/hardware_interface.h>
-
-// Services
-#include <generic_controllers/CalibrateJoint.h>
-
-//FIXME: the editor messed up the indentation
-namespace controller
-{
-
- class JointManualCalibrationController : public Controller
- {
- public:
- /*!
- * \brief Default Constructor.
- *
- */
- JointManualCalibrationController();
-
- /*!
- * \brief Destructor.
- */
- virtual ~JointManualCalibrationController();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- *
- */
- virtual bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /*!
- * \brief Sets the joint in motion to find the reference position.
- *
- * There are two operating modes: manual and automatic.
- * The following algorithm is currently used in automatic mode: the controller sets a search direction for the reference point: positive direction if the current calibration reading is low, negative otherwie. It uses a velocity controller to move the joint in this direction and moves the joint until the calibration reading changes value. It then sets the offset filed in the related transmission accordingly.
- * In manual mode, the joint velocity controller is used to find the min and max limits by exploring the space at low speed.
- *
- */
- virtual void beginCalibration();
-
- virtual void endCalibration();
-
- bool getOffset(double & joint_angle);
-
- /** \brief Sets the offset of the joint
- */
- void setOffset(double joint_angle);
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
- virtual void update();
-
- bool calibrated() const { assert(joint_state_); return joint_state_->calibrated_; }
-
-
- protected:
-
- double offset(double act_pos, double joint_ref_pos);
-
- enum ControllerState {Stop,Search,Initialized,Begin,Idle} ;
-
- mechanism::Joint* joint_; /**< Joint we're controlling. */
- Actuator* actuator_; /** The actuator corresponding to the joint */
- mechanism::Robot *robot_; /**< Pointer to robot structure. */
- mechanism::Transmission * transmission_; /** The transmission associated to the actuator and the joint. */
- mechanism::JointState* joint_state_; /**< Joint we're controlling. */
-
- int state_; /** The current state of the controller*/
-
- double min_; // in actuator position
- double max_; // in actuator position
-
- ros::thread::mutex state_mutex_; /** Mutex locked during the calibration procedure to prevent lousy code from trying to find the offset while it is already searching. */
- };
-
-
- /***************************************************/
-/*! \class controller::JointCalibrationControllerNode
- \brief Joint Limit Controller ROS Node
-
- This class starts and stops the initialization sequence
-
- */
- /***************************************************/
-
- class JointManualCalibrationControllerNode : public Controller
- {
- public:
- /*!
- * \brief Default Constructor
- *
- */
- JointManualCalibrationControllerNode();
-
- /*!
- * \brief Destructor
- */
- virtual ~JointManualCalibrationControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- // Services
- bool beginCalibrationCommand(generic_controllers::CalibrateJoint::request &req,
- generic_controllers::CalibrateJoint::response &resp);
- bool endCalibrationCommand(generic_controllers::CalibrateJoint::request &req,
- generic_controllers::CalibrateJoint::response &resp);
-
- private:
- JointManualCalibrationController *c_;
- };
-}
-
-
Deleted: 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-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_pd_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,198 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointPDController
- \brief Joint Velocity Controller
-
- This class closes the loop around velocity using
- a pid loop.
-
- 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>
- </controller>
-*/
-/***************************************************/
-
-#include <ros/node.h>
-
-#include <generic_controllers/controller.h>
-#include <mechanism_model/pid.h>
-
-// Services
-#include <generic_controllers/SetPDCommand.h>
-#include <generic_controllers/GetPDActual.h>
-#include <generic_controllers/GetPDCommand.h>
-
-namespace controller
-{
-
- class JointPDController : public Controller
- {
- public:
- /*!
- * \brief Default Constructor of the JointController class.
- *
- */
- JointPDController();
-
- /*!
- * \brief Destructor of the JointController class.
- */
- ~JointPDController();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- * \param p_gain Proportional gain.
- * \param i_gain Integral gain.
- * \param d_gain Derivative gain.
- * \param windup Intergral limit.
- * \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::RobotState *robot);
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /*!
- * \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
- *
- * \param double pos Velocity command to issue
- */
- void setPDCommand(double command, double command_dot);
-
- /*!
- * \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
- */
- void getPDCommand(double &command, double &command_dot);
-
- /*!
- * \brief Get latest time..
- */
- double getTime();
-
- /*!
- * \brief Read the torque of the motor
- */
- double getMeasuredVelocity();
-
- /*!
- * \brief Read the torque of the motor
- */
- double getMeasuredPosition();
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
- virtual void update();
-
- void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
-
- void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
-
-
- std::string getJointName();
-
- private:
-
- 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_;
-
- /*!
- * \brief mutex lock for setting and getting commands
- */
- pthread_mutex_t joint_pd_controller_lock_;
-
- };
-
-/***************************************************/
-/*! \class controller::JointPDControllerNode
- \brief Joint Velocity Controller ROS Node
-
- This class closes the loop around velocity using
- a pid loop.
-
- The xml config is the same as for JointPDController except
- the addition of a "topic" attribute, which determines the
- namespace over which messages are published and services are
- offered.
-*/
-/***************************************************/
-
- class JointPDControllerNode : public Controller
- {
- public:
- /*!
- * \brief Default Constructor
- *
- */
- JointPDControllerNode();
-
- /*!
- * \brief Destructor
- */
- ~JointPDControllerNode();
-
- void update();
-
- 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,
- generic_controllers::SetPDCommand::response &resp);
-
- // Services
- bool getPDCommand(generic_controllers::GetPDCommand::request &req,
- generic_controllers::GetPDCommand::response &resp);
-
- bool getPDActual(generic_controllers::GetPDActual::request &req,
- generic_controllers::GetPDActual::response &resp);
-
- private:
- JointPDController *c_;
- };
-}
Deleted: 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-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_position_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,191 +0,0 @@
-/*********************************************************************
- * 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.
- *********************************************************************/
-
-#pragma once
-
-/***************************************************/
-/*! \class controller::JointPositionController
- \brief Joint Position Controller
-
- This class closes the loop around positon using
- a pid loop.
-
- Example config:
-
- <controller type="JointPositionController" name="controller_name" topic="a_topic">
- <joint name="head_tilt_joint">
- <pid p="1.0" i="0.0" d="3.0" iClamp="0.0" />
- </joint>
- </controller>
-
-*/
-/***************************************************/
-
-#include <ros/node.h>
-
-#include <generic_controllers/controller.h>
-#include <mechanism_model/pid.h>
-
-// Services
-#include <generic_controllers/SetCommand.h>
-#include <generic_controllers/GetActual.h>
-
-#include <generic_controllers/SingleJointPosCmd.h>
-
-namespace controller
-{
-
-class JointPositionController : public Controller
-{
-public:
- /*!
- * \brief Default Constructor of the JointPositionController class.
- *
- */
- JointPositionController();
-
- /*!
- * \brief Destructor of the JointPositionController class.
- */
- ~JointPositionController();
-
- /*!
- * \brief Functional way to initialize limits and gains.
- * \param p_gain Proportional gain.
- * \param i_gain Integral gain.
- * \param d_gain Derivative gain.
- * \param windup Intergral limit.
- * \param time The current hardware time.
- * \param *joint The joint that is being controlled.
- */
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /*!
- * \brief Give set position of the joint for next update: revolute (angle) and prismatic (position)
- *
- * \param command
- */
- void setCommand(double command);
-
- /*!
- * \brief Get latest position command to the joint: revolute (angle) and prismatic (position).
- */
- double getCommand();
-
- /*!
- * \brief Read the torque of the motor
- */
- double getMeasuredPosition();
-
- /*!
- * \brief Get latest time..
- */
- double getTime();
-
-
- /*!
- * \brief Issues commands to the joint. Should be called at regular intervals
- */
- virtual void update();
-
- void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
-
- void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
-
- std::string getJointName();
-
-private:
- 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. */
-
- double smoothed_error_; /** */
- double smoothing_factor_;
-
-};
-
-/***************************************************/
-/*! \class controller::JointPositionControllerNode
- \brief Joint Position Controller ROS Node
-
- This class closes the loop around positon using
- a pid loop.
-
-
-*/
-/***************************************************/
-
-class JointPositionControllerNode : public Controller
-{
-public:
- /*!
- * \brief Default Constructor
- *
- */
- JointPositionControllerNode();
-
- /*!
- * \brief Destructor
- */
- ~JointPositionControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- // Services
- bool setCommand(generic_controllers::SetCommand::request &req,
- generic_controllers::SetCommand::response &resp);
- void setCommand(double command);
-
- double getCommand();
-
- double getMeasuredPosition();
-
- bool getActual(generic_controllers::GetActual::request &req,
- generic_controllers::GetActual::response &resp);
-
- /*!
- * \brief ROS topic callback
- */
- void setJointPosSingle();
-
-private:
- generic_controllers::SingleJointPosCmd msg_; //The message used by the ROS callback
- JointPositionController *c_;
-};
-}
-
Deleted: 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-18 23:48:34 UTC (rev 4454)
+++ pkg/trunk/controllers/generic_controllers/include/generic_controllers/joint_velocity_controller.h 2008-09-18 23:50:44 UTC (rev 4455)
@@ -1,173 +0,0 @@
-/*********************************************************************
- * 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 di...
[truncated message content] |