|
From: <stu...@us...> - 2009-08-07 17:54:50
|
Revision: 21031
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21031&view=rev
Author: stuglaser
Date: 2009-08-07 17:54:43 +0000 (Fri, 07 Aug 2009)
Log Message:
-----------
Removed robot_srvs/GetValue for issue #1948
Modified Paths:
--------------
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_position_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_smoothing_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_smoothing_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/pid_position_velocity_controller.h
Removed Paths:
-------------
pkg/trunk/stacks/common_msgs/robot_srvs/srv/GetValue.srv
Modified: 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_effort_controller.h 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_effort_controller.h 2009-08-07 17:54:43 UTC (rev 21031)
@@ -56,9 +56,7 @@
#include "misc_utils/advertised_service_guard.h"
#include "misc_utils/subscription_guard.h"
-// Services
#include <std_msgs/Float64.h>
-#include <robot_srvs/GetValue.h>
namespace controller
Modified: 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_position_controller.h 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_controller.h 2009-08-07 17:54:43 UTC (rev 21031)
@@ -62,7 +62,6 @@
// Services
#include <std_msgs/Float64.h>
-#include <robot_srvs/GetValue.h>
//Realtime publisher
#include <robot_mechanism_controllers/JointControllerState.h>
@@ -115,8 +114,8 @@
mechanism::RobotState *robot_; /**< Pointer to robot structure. */
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
-
+
ros::NodeHandle node_;
boost::scoped_ptr<
@@ -148,19 +147,13 @@
void update();
bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- // Topics
void setCommand();
- //Sevices
- bool getCommand(robot_srvs::GetValue::Request &req,
- robot_srvs::GetValue::Response &resp);
-
private:
//node stuff
std::string service_prefix_; /**< The name of the controller. */
ros::Node *node_;
- AdvertisedServiceGuard guard_get_command_; /**< Makes sure the advertise goes down neatly. */
SubscriptionGuard guard_set_command_; /**< Makes sure the subscription goes down neatly. */
//msgs
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_smoothing_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_smoothing_controller.h 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_position_smoothing_controller.h 2009-08-07 17:54:43 UTC (rev 21031)
@@ -60,7 +60,6 @@
// Services
#include <std_msgs/Float64.h>
-#include <robot_srvs/GetValue.h>
namespace controller
{
@@ -110,7 +109,7 @@
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
double command_; /**< Last commanded position. */
- double smoothed_error_;
+ double smoothed_error_;
double smoothing_factor_;
};
@@ -133,19 +132,13 @@
void update();
bool initXml(mechanism::RobotState *robot, TiXmlElement *config);
- // Topics
void setCommand();
- //Sevices
- bool getCommand(robot_srvs::GetValue::Request &req,
- robot_srvs::GetValue::Response &resp);
-
private:
//node stuff
std::string service_prefix_; /**< The name of the controller. */
ros::Node *node_;
- AdvertisedServiceGuard guard_get_command_; /**< Makes sure the advertise goes down neatly. */
SubscriptionGuard guard_set_command_; /**< Makes sure the subscription goes down neatly. */
//msgs
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_velocity_controller.h 2009-08-07 17:54:43 UTC (rev 21031)
@@ -71,7 +71,6 @@
// Services
#include <std_msgs/Float64.h>
-#include <robot_srvs/GetValue.h>
//Realtime publisher
#include <robot_mechanism_controllers/JointControllerState.h>
@@ -131,7 +130,7 @@
control_toolbox::Pid pid_controller_; /**< Internal PID controller. */
double last_time_; /**< Last time stamp of update. */
int loop_count_;
-
+
friend class JointVelocityControllerNode;
boost::scoped_ptr<
@@ -161,18 +160,13 @@
void update();
bool initXml(mechanism::RobotState *robot_state, TiXmlElement *config);
- // Topics
void setCommand();
- //Services
- bool getCommand(robot_srvs::GetValue::Request &req,
- robot_srvs::GetValue::Response &resp);
private:
//node stuff
std::string service_prefix_; /**< The name of the controller. */
ros::Node *node_;
- AdvertisedServiceGuard guard_get_command_; /**< Makes sure the advertise goes down neatly. */
SubscriptionGuard guard_set_command_; /**< Makes sure the subscription goes down neatly. */
//msgs
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_controller.cpp 2009-08-07 17:54:43 UTC (rev 21031)
@@ -304,9 +304,6 @@
//subscriptions
node_->subscribe(service_prefix_ + "/set_command", cmd_, &JointPositionControllerNode::setCommand, this, 1);
guard_set_command_.set(service_prefix_ + "/set_command");
- //services
- node_->advertiseService(service_prefix_ + "/get_command", &JointPositionControllerNode::getCommand, this);
- guard_get_command_.set(service_prefix_ + "/get_command");
pid_tuner_.add(&c_->pid_controller_);
@@ -320,13 +317,4 @@
c_->setCommand(cmd_.data);
}
-bool JointPositionControllerNode::getCommand(robot_srvs::GetValue::Request &req,
- robot_srvs::GetValue::Response &resp)
-{
- double cmd;
- c_->getCommand(cmd);
- resp.v = cmd;
- return true;
}
-
-}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_smoothing_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_smoothing_controller.cpp 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_position_smoothing_controller.cpp 2009-08-07 17:54:43 UTC (rev 21031)
@@ -191,9 +191,6 @@
//subscriptions
node_->subscribe(service_prefix_ + "/set_command", cmd_, &JointPositionSmoothControllerNode::setCommand, this, 1);
guard_set_command_.set(service_prefix_ + "/set_command");
- //services
- node_->advertiseService(service_prefix_ + "/get_command", &JointPositionSmoothControllerNode::getCommand, this);
- guard_get_command_.set(service_prefix_ + "/get_command");
return true;
}
@@ -203,15 +200,5 @@
c_->setCommand(cmd_.data);
}
-bool JointPositionSmoothControllerNode::getCommand(robot_srvs::GetValue::Request &req,
- robot_srvs::GetValue::Response &resp)
-{
- double cmd;
- c_->getCommand(cmd);
- resp.v = cmd;
- return true;
-}
-
-
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_velocity_controller.cpp 2009-08-07 17:54:43 UTC (rev 21031)
@@ -254,9 +254,6 @@
//subscriptions
node_->subscribe(service_prefix_ + "/set_command", cmd_, &JointVelocityControllerNode::setCommand, this, 1);
guard_set_command_.set(service_prefix_ + "/set_command");
- //services
- node_->advertiseService(service_prefix_ + "/get_command", &JointVelocityControllerNode::getCommand, this);
- guard_get_command_.set(service_prefix_ + "/get_command");
pid_tuner_.add(&c_->pid_controller_);
pid_tuner_.advertise(service_prefix_);
@@ -268,13 +265,4 @@
c_->setCommand(cmd_.data);
}
-bool JointVelocityControllerNode::getCommand(robot_srvs::GetValue::Request &req,
- robot_srvs::GetValue::Response &resp)
-{
- double cmd;
- c_->getCommand(cmd);
- resp.v = cmd;
- return true;
-}
-
} // namespace
Modified: pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/pid_position_velocity_controller.h
===================================================================
--- pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/pid_position_velocity_controller.h 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/sandbox/experimental_controllers/include/experimental_controllers/pid_position_velocity_controller.h 2009-08-07 17:54:43 UTC (rev 21031)
@@ -71,7 +71,6 @@
// Services
#include <std_msgs/Float64.h>
-#include <robot_srvs/GetValue.h>
//Realtime publisher
#include <robot_mechanism_controllers/JointControllerState.h>
Deleted: pkg/trunk/stacks/common_msgs/robot_srvs/srv/GetValue.srv
===================================================================
--- pkg/trunk/stacks/common_msgs/robot_srvs/srv/GetValue.srv 2009-08-07 17:42:00 UTC (rev 21030)
+++ pkg/trunk/stacks/common_msgs/robot_srvs/srv/GetValue.srv 2009-08-07 17:54:43 UTC (rev 21031)
@@ -1,2 +0,0 @@
----
-float64 v
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|