|
From: <mee...@us...> - 2009-08-26 19:05:53
|
Revision: 23002
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23002&view=rev
Author: meeussen
Date: 2009-08-26 19:05:33 +0000 (Wed, 26 Aug 2009)
Log Message:
-----------
make init function mandatory for controllers. remove controllers that do not implement init function from makefile (those controllers haven't worked for more than a month now). open door test passes
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/src/controller_manifest.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp
pkg/trunk/sandbox/experimental_controllers/CMakeLists.txt
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/arm_trajectory_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_autotuner.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_chain_constraint_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_pd_controller.h
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_position_smoothing_controller.h
pkg/trunk/sandbox/experimental_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/controller_manifest.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_autotuner.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_chain_constraint_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_pd_controller.cpp
pkg/trunk/sandbox/experimental_controllers/src/joint_position_smoothing_controller.cpp
pkg/trunk/stacks/mechanism/controller_interface/include/controller_interface/controller.h
Removed Paths:
-------------
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/dynamic_loader_controller.h
pkg/trunk/sandbox/experimental_controllers/src/dynamic_loader_controller.cpp
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -34,19 +34,8 @@
#pragma once
-/*
- Example XML:
- <controller type="GripperCalibrationController">
- <calibrate joint="upperarm_roll_right_joint"
- actuator="upperarm_roll_right_act"
- transmission="upperarm_roll_right_trans"
- velocity="0.3" />
- <pid p="15" i="0" d="0" iClamp="0" />
- </controller>
-*/
-
#include "mechanism_model/robot.h"
#include "robot_mechanism_controllers/joint_velocity_controller.h"
#include "realtime_tools/realtime_publisher.h"
@@ -93,42 +82,6 @@
};
-/***************************************************/
-/*! \class controller::GripperCalibrationControllerNode
- \brief Joint Limit Controller ROS Node
-
- This class starts and stops the initialization sequence
-
-*/
-/***************************************************/
-
-class GripperCalibrationControllerNode : public Controller
-{
-public:
- /*!
- * \brief Default Constructor
- *
- */
- GripperCalibrationControllerNode();
-
- /*!
- * \brief Destructor
- */
- ~GripperCalibrationControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
-
-private:
- mechanism::RobotState* robot_;
- GripperCalibrationController c_;
-
- double last_publish_time_;
- realtime_tools::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
-};
-
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -98,24 +98,6 @@
};
-class WristCalibrationControllerNode : public Controller
-{
-public:
- WristCalibrationControllerNode();
- ~WristCalibrationControllerNode();
-
- void update();
-
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
-private:
- mechanism::RobotState *robot_;
- WristCalibrationController c_;
-
- double last_publish_time_;
- realtime_tools::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
-};
-
}
#endif
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/controller_manifest.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/controller_manifest.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/controller_manifest.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -47,7 +47,6 @@
PLUGINLIB_REGISTER_CLASS(CasterCalibrationController, CasterCalibrationController, Controller)
PLUGINLIB_REGISTER_CLASS(CasterController, CasterController, Controller)
PLUGINLIB_REGISTER_CLASS(GripperCalibrationController, GripperCalibrationController, Controller)
-PLUGINLIB_REGISTER_CLASS(GripperCalibrationControllerNode, GripperCalibrationControllerNode, Controller)
PLUGINLIB_REGISTER_CLASS(HeadPositionController, HeadPositionController, Controller)
PLUGINLIB_REGISTER_CLASS(LaserScannerTrajController, LaserScannerTrajController, Controller)
PLUGINLIB_REGISTER_CLASS(LaserScannerTrajControllerNode, LaserScannerTrajControllerNode, Controller)
@@ -55,6 +54,5 @@
//PLUGINLIB_REGISTER_CLASS(Pr2GripperController, Pr2GripperController, Controller)
PLUGINLIB_REGISTER_CLASS(Pr2Odometry, Pr2Odometry, Controller)
PLUGINLIB_REGISTER_CLASS(WristCalibrationController, WristCalibrationController, Controller)
-PLUGINLIB_REGISTER_CLASS(WristCalibrationControllerNode, WristCalibrationControllerNode, Controller)
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -41,7 +41,6 @@
namespace controller
{
-ROS_REGISTER_CONTROLLER(GripperCalibrationController)
GripperCalibrationController::GripperCalibrationController()
: state_(INITIALIZED), last_publish_time_(0), joint_(NULL)
@@ -207,52 +206,4 @@
}
-ROS_REGISTER_CONTROLLER(GripperCalibrationControllerNode)
-
-GripperCalibrationControllerNode::GripperCalibrationControllerNode()
-: robot_(NULL), last_publish_time_(0)
-{
}
-
-GripperCalibrationControllerNode::~GripperCalibrationControllerNode()
-{
-}
-
-void GripperCalibrationControllerNode::update()
-{
- c_.update();
-
- if (c_.calibrated())
- {
- if (last_publish_time_ + 0.5 < robot_->getTime())
- {
- assert(pub_calibrated_);
- if (pub_calibrated_->trylock())
- {
- last_publish_time_ = robot_->getTime();
- pub_calibrated_->unlockAndPublish();
- }
- }
- }
-}
-
-bool GripperCalibrationControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
-{
- robot_ = robot;
-
- std::string topic = config->Attribute("name") ? config->Attribute("name") : "";
- if (topic == "")
- {
- fprintf(stderr, "No name given to GripperCalibrationController\n");
- return false;
- }
-
- if (!c_.initXml(robot, config))
- return false;
-
- pub_calibrated_ = new realtime_tools::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
-
- return true;
-}
-
-}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -35,7 +35,6 @@
namespace controller {
-ROS_REGISTER_CONTROLLER(WristCalibrationController)
WristCalibrationController::WristCalibrationController()
: state_(INITIALIZED), robot_(NULL), last_publish_time_(0)
@@ -384,55 +383,4 @@
}
-ROS_REGISTER_CONTROLLER(WristCalibrationControllerNode)
-
-WristCalibrationControllerNode::WristCalibrationControllerNode()
-: last_publish_time_(0), pub_calibrated_(NULL)
-{
}
-
-WristCalibrationControllerNode::~WristCalibrationControllerNode()
-{
- if (pub_calibrated_)
- delete pub_calibrated_;
-}
-
-void WristCalibrationControllerNode::update()
-{
- c_.update();
-
- if (c_.calibrated())
- {
- if (last_publish_time_ + 0.5 < robot_->getTime())
- {
- assert(pub_calibrated_);
- if (pub_calibrated_->trylock())
- {
- last_publish_time_ = robot_->getTime();
- pub_calibrated_->unlockAndPublish();
- }
- }
- }
-}
-
-bool WristCalibrationControllerNode::initXml(mechanism::RobotState *robot, TiXmlElement *config)
-{
- assert(robot);
- robot_ = robot;
-
- std::string name = config->Attribute("name") ? config->Attribute("name") : "";
- if (name == "")
- {
- fprintf(stderr, "No name given to WristCalibrationController\n");
- return false;
- }
-
- if (!c_.initXml(robot, config))
- return false;
-
- pub_calibrated_ = new realtime_tools::RealtimePublisher<std_msgs::Empty>(name + "/calibrated", 1);
-
- return true;
-}
-
-}
Modified: pkg/trunk/sandbox/experimental_controllers/CMakeLists.txt
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/CMakeLists.txt 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/CMakeLists.txt 2009-08-26 19:05:33 UTC (rev 23002)
@@ -33,16 +33,15 @@
src/cartesian_tff_controller.cpp
src/cartesian_twist_controller_ik.cpp
src/cartesian_hybrid_controller.cpp
- src/dynamic_loader_controller.cpp
- src/joint_position_smoothing_controller.cpp
+# src/joint_position_smoothing_controller.cpp
src/joint_inverse_dynamics_controller.cpp
- src/joint_autotuner.cpp
- src/joint_calibration_controller.cpp
- src/joint_limit_calibration_controller.cpp
- src/joint_blind_calibration_controller.cpp
+# src/joint_autotuner.cpp
+# src/joint_calibration_controller.cpp
+# src/joint_limit_calibration_controller.cpp
+# src/joint_blind_calibration_controller.cpp
src/joint_chain_constraint_controller.cpp
- src/joint_chain_sine_controller.cpp
- src/probe.cpp
+# src/joint_chain_sine_controller.cpp
+# src/probe.cpp
src/head_servoing_controller.cpp
src/arm_trajectory_controller.cpp
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/arm_trajectory_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/arm_trajectory_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/arm_trajectory_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -75,7 +75,7 @@
// The maximum number of joints expected in an arm.
static const int MAX_ARM_JOINTS = 7;
- class ArmTrajectoryController : public Controller
+ class ArmTrajectoryController
{
public:
Deleted: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/dynamic_loader_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/dynamic_loader_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/dynamic_loader_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -1,113 +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.
- */
-
-/*
- * Author: Rob Wheeler
- */
-
-#ifndef DYNAMIC_LOADER_CONTROLLER_H
-#define DYNAMIC_LOADER_CONTROLLER_H
-
-#include "controller_interface/controller.h"
-#include <tinyxml/tinyxml.h>
-#include <ltdl.h>
-
-namespace controller {
-
-/***************************************************/
-/*! \class controller::DynamicLoaderController
- \brief Dynamic Loader
-
- This class implements a pseudo-controller that can dynamically
- load a package's shared object and instantiate controllers from
- that shared object.
-
- When the DynamicLoaderController is killed, it shuts down the
- controllers that it started and unloads the shared object.
-
- Example configuration:
- <pre>
- <controller name="dynamic_loader" type="DynamicLoaderController"
- package="my_controllers" lib="libmy_controllers">
-
- <controllers>
-
- <controller type="MyController" name="my_controller1">
- <joint name="joint_to_control" />
- </controller><br>
-
- <controller type="MyController" name="my_controller2">
- <joint name="another_joint_to_control" />
- </controller><br>
-
- </controllers>
-
- </controller>
- </pre>
-
- The above example creates an instance of the DynamicLoaderController
- that loads the shared object libmy_controllers.so from the
- my_controllers package. It then instantiates two controllers,
- my_controller1 and my_controller2, from that shared object.
- When the DynamicLoaderController is killed, it will kill the two
- controllers it started and unload the libmy_controllers.so shared object.
-
-*/
-/***************************************************/
-
-class DynamicLoaderController : public Controller
-{
-public:
- DynamicLoaderController();
- ~DynamicLoaderController();
-
- /*!
- * \brief Specifies the package and shared object to load.
- * \param *robot The robot (not used by this controller).
- * \param *config The XML configuration for this controller
- */
- bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
-
- /*!
- * \brief This function is called in the control loop. For this
- * pseudo-controller, the update function is a noop.
- */
- void update();
-
-private:
- std::vector<std::string> names_;
- lt_dlhandle handle_;
-
- void loadLibrary(std::string& name);
- static void unloadLibrary(std::vector<std::string> names, lt_dlhandle handle);
-};
-
-}
-
-#endif
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_autotuner.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_autotuner.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_autotuner.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -162,19 +162,11 @@
*/
/***************************************************/
-
class JointAutotunerNode : public Controller
{
public:
- /*!
- * \brief Default Constructor
- *
- */
JointAutotunerNode();
- /*!
- * \brief Destructor
- */
~JointAutotunerNode();
void update();
@@ -191,5 +183,6 @@
private:
JointAutotuner *c_;
};
+
}
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_chain_constraint_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_chain_constraint_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_chain_constraint_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -155,6 +155,7 @@
+/*
class JointChainConstraintControllerNode : public Controller
{
public:
@@ -177,7 +178,7 @@
};
-
+*/
} // namespace
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_pd_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_pd_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_pd_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -53,10 +53,10 @@
#include <ros/node.h>
-#include <controller_interface/controller.h>
#include <control_toolbox/pid.h>
#include "misc_utils/advertised_service_guard.h"
#include "misc_utils/subscription_guard.h"
+#include <mechanism_model/robot.h>
// Services
#include <experimental_controllers/SetPDCommand.h>
@@ -66,7 +66,7 @@
namespace controller
{
- class JointPDController : public Controller
+ class JointPDController
{
public:
@@ -138,7 +138,7 @@
*/
/***************************************************/
- class JointPDControllerNode : public Controller
+ class JointPDControllerNode
{
public:
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_position_smoothing_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_position_smoothing_controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/joint_position_smoothing_controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -122,6 +122,7 @@
*/
/***************************************************/
+
class JointPositionSmoothControllerNode : public Controller
{
public:
@@ -148,5 +149,6 @@
JointPositionSmoothController *c_; /**< The controller. */
};
+
}
Modified: pkg/trunk/sandbox/experimental_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/arm_trajectory_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/arm_trajectory_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -41,7 +41,6 @@
using namespace controller;
using namespace std;
-ROS_REGISTER_CONTROLLER(ArmTrajectoryController);
static const std::string JointTrajectoryStatusString[7] = {"0 - ACTIVE","1 - DONE","2 - QUEUED","3 - DELETED","4 - FAILED","5 - CANCELED","6 - NUM_STATUS"};
Modified: pkg/trunk/sandbox/experimental_controllers/src/controller_manifest.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/controller_manifest.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/controller_manifest.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -38,17 +38,16 @@
#include "experimental_controllers/cartesian_hybrid_controller.h"
#include "experimental_controllers/cartesian_twist_controller_ik.h"
-#include "experimental_controllers/dynamic_loader_controller.h"
//#include "experimental_controllers/endeffector_constraint_controller.h"
-#include "experimental_controllers/joint_autotuner.h"
-#include "experimental_controllers/joint_blind_calibration_controller.h"
-#include "experimental_controllers/joint_calibration_controller.h"
+//#include "experimental_controllers/joint_autotuner.h"
+//#include "experimental_controllers/joint_blind_calibration_controller.h"
+//#include "experimental_controllers/joint_calibration_controller.h"
#include "experimental_controllers/joint_chain_constraint_controller.h"
-#include "experimental_controllers/joint_chain_sine_controller.h"
+//#include "experimental_controllers/joint_chain_sine_controller.h"
#include "experimental_controllers/joint_inverse_dynamics_controller.h"
-#include "experimental_controllers/joint_limit_calibration_controller.h"
-#include "experimental_controllers/joint_position_smoothing_controller.h"
-#include "experimental_controllers/probe.h"
+//#include "experimental_controllers/joint_limit_calibration_controller.h"
+//#include "experimental_controllers/joint_position_smoothing_controller.h"
+//#include "experimental_controllers/probe.h"
#include "experimental_controllers/head_servoing_controller.h"
#include "experimental_controllers/joint_trajectory_controller.h"
@@ -64,26 +63,25 @@
//PLUGINLIB_REGISTER_CLASS(PlugControllerNode, PlugControllerNode, Controller)
PLUGINLIB_REGISTER_CLASS(TrajectoryController, TrajectoryController, Controller)
-PLUGINLIB_REGISTER_CLASS(DynamicLoaderController, DynamicLoaderController, Controller)
+//PLUGINLIB_REGISTER_CLASS(DynamicLoaderController, DynamicLoaderController, Controller)
-PLUGINLIB_REGISTER_CLASS(Probe, Probe, Controller)
+//PLUGINLIB_REGISTER_CLASS(Probe, Probe, Controller)
PLUGINLIB_REGISTER_CLASS(CartesianTFFController, CartesianTFFController, Controller)
PLUGINLIB_REGISTER_CLASS(CartesianHybridController, CartesianHybridController, Controller)
PLUGINLIB_REGISTER_CLASS(CartesianHybridControllerNode, CartesianHybridControllerNode, Controller)
//PLUGINLIB_REGISTER_CLASS(EndeffectorConstraintController, EndeffectorConstraintController, Controller)
//PLUGINLIB_REGISTER_CLASS(EndeffectorConstraintControllerNode, EndeffectorConstraintControllerNode, Controller)
-PLUGINLIB_REGISTER_CLASS(JointChainConstraintControllerNode, JointChainConstraintControllerNode, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointChainConstraintControllerNode, JointChainConstraintControllerNode, Controller)
PLUGINLIB_REGISTER_CLASS(JointInverseDynamicsController, JointInverseDynamicsController, Controller);
-PLUGINLIB_REGISTER_CLASS(JointPositionSmoothController, JointPositionSmoothController, Controller)
-PLUGINLIB_REGISTER_CLASS(JointPositionSmoothControllerNode, JointPositionSmoothControllerNode, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointPositionSmoothController, JointPositionSmoothController, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointPositionSmoothControllerNode, JointPositionSmoothControllerNode, Controller)
-PLUGINLIB_REGISTER_CLASS(JointAutotuner, JointAutotuner, Controller)
-PLUGINLIB_REGISTER_CLASS(JointAutotunerNode, JointAutotunerNode, Controller)
-PLUGINLIB_REGISTER_CLASS(JointBlindCalibrationController, JointBlindCalibrationController, Controller)
-PLUGINLIB_REGISTER_CLASS(JointBlindCalibrationControllerNode,JointBlindCalibrationControllerNode, Controller)
-PLUGINLIB_REGISTER_CLASS(JointCalibrationControllerNode,JointCalibrationControllerNode, Controller)
-PLUGINLIB_REGISTER_CLASS(JointChainSineController,JointChainSineController, Controller)
-PLUGINLIB_REGISTER_CLASS(JointLimitCalibrationControllerNode,JointLimitCalibrationControllerNode, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointAutotuner, JointAutotuner, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointBlindCalibrationController, JointBlindCalibrationController, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointBlindCalibrationControllerNode,JointBlindCalibrationControllerNode, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointCalibrationControllerNode,JointCalibrationControllerNode, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointChainSineController,JointChainSineController, Controller)
+//PLUGINLIB_REGISTER_CLASS(JointLimitCalibrationControllerNode,JointLimitCalibrationControllerNode, Controller)
PLUGINLIB_REGISTER_CLASS(CartesianTwistControllerIk,CartesianTwistControllerIk, Controller)
PLUGINLIB_REGISTER_CLASS(HeadServoingController, HeadServoingController, Controller)
Deleted: pkg/trunk/sandbox/experimental_controllers/src/dynamic_loader_controller.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/dynamic_loader_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/dynamic_loader_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -1,143 +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.
- */
-
-/*
- * Author: Rob Wheeler
- */
-
-#include "experimental_controllers/dynamic_loader_controller.h"
-#include "mechanism_msgs/SpawnController.h"
-#include "mechanism_msgs/KillController.h"
-#include <iostream>
-
-#include <boost/thread.hpp>
-#include <boost/foreach.hpp>
-#include <boost/algorithm/string/trim.hpp>
-#include <ros/ros.h>
-
-namespace controller {
-
-ROS_REGISTER_CONTROLLER(DynamicLoaderController)
-
-DynamicLoaderController::DynamicLoaderController() : handle_(0)
-{
-}
-
-DynamicLoaderController::~DynamicLoaderController()
-{
- // Shutdown controller cleanly
- boost::thread killThread(boost::bind(DynamicLoaderController::unloadLibrary, names_, handle_));
-}
-
-void DynamicLoaderController::unloadLibrary(std::vector<std::string> names, lt_dlhandle handle)
-{
- mechanism_msgs::KillController::Request req;
- mechanism_msgs::KillController::Response resp;
-
- BOOST_FOREACH(std::string &name, names) {
- req.name = name;
-
- ros::service::call("kill_controller", req, resp);
- }
-
- lt_dlclose(handle);
-}
-
-void DynamicLoaderController::loadLibrary(std::string &name)
-{
- mechanism_msgs::SpawnController::Request req;
- mechanism_msgs::SpawnController::Response resp;
-
- req.name = name;
-
- ros::service::call("spawn_controller", req, resp);
-
- /** \todo Remember to start the controller */
-
- names_.clear();
- if (resp.ok)
- names_.push_back(name);
-}
-
-bool DynamicLoaderController::initXml(mechanism::RobotState *robot, TiXmlElement *config)
-{
- std::string package = config->Attribute("package") ? config->Attribute("package") : "";
- if (package == "") {
- ROS_ERROR("No package given to DynamicLoaderController");
- return false;
- }
-
- std::string lib = config->Attribute("lib") ? config->Attribute("lib") : "";
- if (lib == "") {
- ROS_ERROR("No lib given to DynamicLoaderController");
- return false;
- }
-
- std::string command = "rospack find " + package;
- std::string package_dir;
- char buffer[256];
- FILE *pipe = popen(command.c_str(), "r");
- if (pipe == NULL) {
- ROS_ERROR("Unable to run command: %s", command.c_str());
- return false;
- }
- while (fgets(buffer, sizeof(buffer), pipe) != NULL)
- package_dir.append(buffer);
- pclose(pipe);
-
- int errors = lt_dlinit();
- if (errors) {
- ROS_ERROR("Unable to initialize dynamic loader (%s)", lt_dlerror());
- return false;
- }
-
- std::stringstream path;
- path << boost::algorithm::trim_copy(package_dir) << "/lib/" << lib;
-
- if ((handle_ = lt_dlopenext(path.str().c_str())) == NULL) {
- ROS_ERROR("Unable to dlopen %s: %s", path.str().c_str(), lt_dlerror());
- return false;
- }
-
- TiXmlElement *controller = config->FirstChildElement();
-
- if (controller) {
- std::stringstream str;
- str << *controller;
- boost::thread spawnThread(boost::bind(&DynamicLoaderController::loadLibrary, this, str.str()));
- }
-
- return true;
-}
-
-void DynamicLoaderController::update()
-{
-}
-
-}
Modified: pkg/trunk/sandbox/experimental_controllers/src/joint_autotuner.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/joint_autotuner.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/joint_autotuner.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -304,6 +304,8 @@
}
+/*
+
ROS_REGISTER_CONTROLLER(JointAutotunerNode)
JointAutotunerNode::JointAutotunerNode()
{
@@ -361,3 +363,4 @@
}
+*/
Modified: pkg/trunk/sandbox/experimental_controllers/src/joint_chain_constraint_controller.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/joint_chain_constraint_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/joint_chain_constraint_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -296,7 +296,7 @@
-ROS_REGISTER_CONTROLLER(JointChainConstraintControllerNode)
+/*
JointChainConstraintControllerNode::JointChainConstraintControllerNode()
: node_(ros::Node::instance())
@@ -353,6 +353,6 @@
controller_.wrench_desired_(5) = wrench_msg_.torque.z;
}
-
+*/
}; // namespace
Modified: pkg/trunk/sandbox/experimental_controllers/src/joint_pd_controller.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/joint_pd_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/joint_pd_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -40,12 +40,6 @@
using namespace controller;
-PLUGINLIB_REGISTER_CLASS(JointPDController, JointPDController, Controller)
-PLUGINLIB_REGISTER_CLASS(JointPDControllerNode, JointPDControllerNode, Controller)
-
-
-ROS_REGISTER_CONTROLLER(JointPDController)
-
JointPDController::JointPDController()
: joint_state_(NULL), robot_(NULL), last_time_(0), command_(0), command_dot_(0)
{
@@ -180,7 +174,6 @@
//------ Joint PD controller node --------
-ROS_REGISTER_CONTROLLER(JointPDControllerNode)
JointPDControllerNode::JointPDControllerNode(): node_(ros::Node::instance())
{
Modified: pkg/trunk/sandbox/experimental_controllers/src/joint_position_smoothing_controller.cpp
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/src/joint_position_smoothing_controller.cpp 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/sandbox/experimental_controllers/src/joint_position_smoothing_controller.cpp 2009-08-26 19:05:33 UTC (rev 23002)
@@ -39,7 +39,6 @@
using namespace controller;
-ROS_REGISTER_CONTROLLER(JointPositionSmoothController)
JointPositionSmoothController::JointPositionSmoothController()
: joint_state_(NULL), robot_(NULL), last_time_(0), command_(0),smoothed_error_(0), smoothing_factor_(1)
@@ -162,6 +161,7 @@
last_time_ = time;
}
+/*
//------ Joint Position controller node --------
ROS_REGISTER_CONTROLLER(JointPositionSmoothControllerNode)
@@ -202,3 +202,4 @@
+*/
Modified: pkg/trunk/stacks/mechanism/controller_interface/include/controller_interface/controller.h
===================================================================
--- pkg/trunk/stacks/mechanism/controller_interface/include/controller_interface/controller.h 2009-08-26 19:04:03 UTC (rev 23001)
+++ pkg/trunk/stacks/mechanism/controller_interface/include/controller_interface/controller.h 2009-08-26 19:05:33 UTC (rev 23002)
@@ -68,11 +68,7 @@
virtual bool stopping() {return true;}
/// The init function is called to initialize the controller from a non-realtime thread
- virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n)
- {
- ROS_ERROR("Controller %s did not implement init function", n.getNamespace().c_str());
- return false;
- }
+ virtual bool init(mechanism::RobotState *robot, const ros::NodeHandle &n) = 0;
/// Method to get access to another controller by name and type.
template<class ControllerType> bool getController(const std::string& name, int sched, ControllerType*& c)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|