|
From: <rob...@us...> - 2009-01-18 18:49:57
|
Revision: 9673
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=9673&view=rev
Author: rob_wheeler
Date: 2009-01-18 18:49:35 +0000 (Sun, 18 Jan 2009)
Log Message:
-----------
Move realtime publisher and realtime infuser into realtime tools.
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_arm_dynamics_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/sine_sweep_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_orientation_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_position_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_velocity_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_calibration_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_velocity_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/robot_control_loops/pr2_etherCAT/manifest.xml
pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp
pkg/trunk/util/misc_utils/manifest.xml
Added Paths:
-----------
pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_infuser.h
pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_publisher.h
Removed Paths:
-------------
pkg/trunk/util/misc_utils/include/misc_utils/realtime_infuser.h
pkg/trunk/util/misc_utils/include/misc_utils/realtime_publisher.h
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -58,7 +58,7 @@
#include <pr2_msgs/Odometer.h>
#include <pr2_msgs/Covariance2D.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <tf/tfMessage.h>
#include <tf/tf.h>
@@ -481,13 +481,13 @@
double odom_publish_rate_; /** rate at which odometry message will be published ( = 1/odom_publish_delta_t_)*/
- misc_utils::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
- misc_utils::RealtimePublisher <tf::tfMessage>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <tf::tfMessage>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
- misc_utils::RealtimePublisher <pr2_msgs::Odometer>* odometer_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_msgs::Odometer>* odometer_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
- misc_utils::RealtimePublisher <pr2_msgs::Covariance2D>* covariance_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_msgs::Covariance2D>* covariance_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
/*
* \brief pointer to ros node
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/base_controller_pos.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -60,7 +60,7 @@
#include <pr2_msgs/Odometer.h>
#include <pr2_msgs/Covariance2D.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <tf/tfMessage.h>
@@ -499,15 +499,15 @@
double odom_publish_rate_; /** rate at which odometry message will be published ( = 1/odom_publish_delta_t_)*/
- misc_utils::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom>* publisher_ ; //!< Publishes the odometry msg from the update() realtime loop
- misc_utils::RealtimePublisher <tf::tfMessage>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <tf::tfMessage>* transform_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
- misc_utils::RealtimePublisher <pr2_msgs::Odometer>* odometer_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_msgs::Odometer>* odometer_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
- misc_utils::RealtimePublisher <pr2_msgs::Covariance2D>* covariance_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_msgs::Covariance2D>* covariance_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
- misc_utils::RealtimePublisher <pr2_mechanism_controllers::OdometryResiduals>* residuals_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_mechanism_controllers::OdometryResiduals>* residuals_publisher_ ; //!< Publishes the odom to base transform msg from the update() realtime loop
/*
* \brief pointer to ros node
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/caster_calibration_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -35,7 +35,7 @@
#define CASTER_CALIBRATION_CONTROLLER_H
#include "pr2_mechanism_controllers/caster_controller.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "std_msgs/Empty.h"
#include <robot_mechanism_controllers/CalibrateJoint.h>
@@ -97,7 +97,7 @@
AdvertisedServiceGuard guard_calibrate_;
double last_publish_time_;
- misc_utils::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
+ realtime_tools::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
};
}
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-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/gripper_calibration_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -49,7 +49,7 @@
#include "mechanism_model/robot.h"
#include "robot_mechanism_controllers/joint_velocity_controller.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "std_msgs/Empty.h"
namespace controller
@@ -120,7 +120,7 @@
GripperCalibrationController c_;
double last_publish_time_;
- misc_utils::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
+ realtime_tools::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
};
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -39,7 +39,7 @@
#include <mechanism_model/controller.h>
#include <robot_mechanism_controllers/joint_position_smoothing_controller.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
// Messages
#include <pr2_mechanism_controllers/LaserScannerSignal.h>
@@ -257,7 +257,7 @@
LaserScannerController::ProfileExecutionState prev_profile_exec_state_ ; //!< Store the previous profileExecutionState. Need this to compare to the current state to detect transitions
pr2_mechanism_controllers::LaserScannerSignal m_scanner_signal_ ; //!< Stores the message that we want to send at the end of each sweep, and halfway through each sweep
bool need_to_send_msg_ ; //!< Tracks whether we still need to send out the m_scanner_signal_ message.
- misc_utils::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
};
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -39,7 +39,7 @@
#include <mechanism_model/controller.h>
#include <robot_mechanism_controllers/joint_position_smoothing_controller.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include "filters/transfer_function.h"
@@ -145,7 +145,7 @@
pr2_mechanism_controllers::LaserScannerSignal m_scanner_signal_ ; //!< Stores the message that we want to send at the end of each sweep, and halfway through each sweep
bool need_to_send_msg_ ; //!< Tracks whether we still need to send out the m_scanner_signal_ message.
- misc_utils::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
};
}
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-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/wrist_calibration_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -44,7 +44,7 @@
#define WRIST_CALIBRATION_CONTROLLER_H
#include "robot_mechanism_controllers/joint_velocity_controller.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "mechanism_model/wrist_transmission.h"
#include "std_msgs/Empty.h"
@@ -108,7 +108,7 @@
WristCalibrationController c_;
double last_publish_time_;
- misc_utils::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
+ realtime_tools::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
};
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -10,6 +10,7 @@
<depend package="wg_robot_description_parser" />
<depend package="stl_utils" />
<depend package="misc_utils" />
+ <depend package="realtime_tools" />
<depend package="robot_mechanism_controllers" />
<depend package="rospy" />
<depend package="libTF" />
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -35,7 +35,7 @@
// Original version: Sachin Chitta <sa...@wi...>
#include "pr2_mechanism_controllers/arm_trajectory_controller.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "std_msgs/String.h"
using namespace controller;
@@ -228,7 +228,7 @@
double end_time = now();
- static misc_utils::RealtimePublisher<std_msgs::String> p("/s", 1);
+ static realtime_tools::RealtimePublisher<std_msgs::String> p("/s", 1);
if (p.trylock()) {
char buf[1000];
sprintf(buf, "Time = %15.6lf\n", end_time - start_time);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -1002,19 +1002,19 @@
if (publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new misc_utils::RealtimePublisher <std_msgs::RobotBase2DOdom> ("odom", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom> ("odom", 1) ;
if (odometer_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete odometer_publisher_ ;
- odometer_publisher_ = new misc_utils::RealtimePublisher <pr2_msgs::Odometer> (service_prefix + "/odometer", 1) ;
+ odometer_publisher_ = new realtime_tools::RealtimePublisher <pr2_msgs::Odometer> (service_prefix + "/odometer", 1) ;
if (transform_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete transform_publisher_ ;
- transform_publisher_ = new misc_utils::RealtimePublisher <tf::tfMessage> ("tf_message", 5) ;
+ transform_publisher_ = new realtime_tools::RealtimePublisher <tf::tfMessage> ("tf_message", 5) ;
if (covariance_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete covariance_publisher_ ;
- covariance_publisher_ = new misc_utils::RealtimePublisher <pr2_msgs::Covariance2D> (service_prefix + "/odometry_covariance", 1) ;
+ covariance_publisher_ = new realtime_tools::RealtimePublisher <pr2_msgs::Covariance2D> (service_prefix + "/odometry_covariance", 1) ;
node->param<double>("base_controller/odom_publish_rate",odom_publish_rate_,100);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_controller_pos.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -33,7 +33,7 @@
*********************************************************************/
#include <pr2_mechanism_controllers/base_controller_pos.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <control_toolbox/filters.h>
#include <angles/angles.h>
#include <std_msgs/String.h>
@@ -532,7 +532,7 @@
cmd_vel_trajectory_->setTrajectory(cmd_vel_points_);
-/* static misc_utils::RealtimePublisher<std_msgs::String> p("/s", 1);
+/* static realtime_tools::RealtimePublisher<std_msgs::String> p("/s", 1);
if (p.trylock()) {
char buf[1000];
sprintf(buf, "Time = %15.6lf dirn: %1.6f %1.6f %1.6f mag: %1.6f\n Angles: %f %f \n Current dirn: %1.6f %1.6f %1.6f mag: %1.6f\n New cmd: %1.6f %1.6f %1.6f\n Old cmd: %1.6f %1.6f %1.6f\n ",dt,new_vel_direction.x,new_vel_direction.y,new_vel_direction.z,new_cmd_mag,delta_direction,delta_direction_m_pi,cmd_vel_direction_.x,cmd_vel_direction_.y,cmd_vel_direction_.z,cmd_vel_magnitude_,new_cmd.x, new_cmd.y,new_cmd.z,cmd_vel_.x,cmd_vel_.y,cmd_vel_.z);
@@ -1138,23 +1138,23 @@
if (publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new misc_utils::RealtimePublisher <std_msgs::RobotBase2DOdom> ("odom", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <std_msgs::RobotBase2DOdom> ("odom", 1) ;
if (odometer_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete odometer_publisher_ ;
- odometer_publisher_ = new misc_utils::RealtimePublisher <pr2_msgs::Odometer> (service_prefix + "/odometer", 1) ;
+ odometer_publisher_ = new realtime_tools::RealtimePublisher <pr2_msgs::Odometer> (service_prefix + "/odometer", 1) ;
if (transform_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete transform_publisher_ ;
- transform_publisher_ = new misc_utils::RealtimePublisher <tf::tfMessage> ("tf_message", 5) ;
+ transform_publisher_ = new realtime_tools::RealtimePublisher <tf::tfMessage> ("tf_message", 5) ;
if (covariance_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete covariance_publisher_ ;
- covariance_publisher_ = new misc_utils::RealtimePublisher <pr2_msgs::Covariance2D> (service_prefix + "/odometry_covariance", 1) ;
+ covariance_publisher_ = new realtime_tools::RealtimePublisher <pr2_msgs::Covariance2D> (service_prefix + "/odometry_covariance", 1) ;
if (residuals_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete residuals_publisher_ ;
- residuals_publisher_ = new misc_utils::RealtimePublisher <pr2_mechanism_controllers::OdometryResiduals> (service_prefix + "/odometry_residuals", 1) ;
+ residuals_publisher_ = new realtime_tools::RealtimePublisher <pr2_mechanism_controllers::OdometryResiduals> (service_prefix + "/odometry_residuals", 1) ;
node->param<double>("base_controller/odom_publish_rate",odom_publish_rate_,100);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/caster_calibration_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -213,7 +213,7 @@
node->advertiseService(topic + "/calibrate", &CasterCalibrationControllerNode::calibrateCommand, this);
guard_calibrate_.set(topic + "/calibrate");
- pub_calibrated_ = new misc_utils::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
+ pub_calibrated_ = new realtime_tools::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
return true;
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/gripper_calibration_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -185,7 +185,7 @@
if (!c_.initXml(robot, config))
return false;
- pub_calibrated_ = new misc_utils::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
+ pub_calibrated_ = new realtime_tools::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
return true;
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -559,7 +559,7 @@
if (publisher_ != NULL) // Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new misc_utils::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
return true;
}
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -413,7 +413,7 @@
if (publisher_ != NULL) // Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new misc_utils::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
prev_profile_time_ = 0.0 ;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_arm_dynamics_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_arm_dynamics_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/pr2_arm_dynamics_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -35,7 +35,7 @@
// Original version: Sachin Chitta <sa...@wi...>
#include "pr2_mechanism_controllers/pr2_arm_dynamics_controller.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "std_msgs/String.h"
// Math utils
@@ -255,7 +255,7 @@
control_torque_[i] = gravity_torque_[i][2] + pid_torque;
// fprintf(stderr,"%d:: %f, %f, %f, %f, %f, %f, %f\n",i,actual,command,error,pid_torque,gravity_torque_[i][2],control_torque_[i],time-last_time_);
- static misc_utils::RealtimePublisher<std_msgs::String> p("/s", 1);
+ static realtime_tools::RealtimePublisher<std_msgs::String> p("/s", 1);
if (p.trylock()) {
char buf[1000];
sprintf(buf, "Joint torques %d:: %s, %15.6lf %15.61f %15.61f %15.61f\n", i, joint_effort_controllers_[i]->joint_state_->joint_->name_.c_str(),control_torque_[i],gravity_torque_[i][2],gravity_torque_uncompensated_[i][2],pid_torque);
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/wrist_calibration_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -307,7 +307,7 @@
if (!c_.initXml(robot, config))
return false;
- pub_calibrated_ = new misc_utils::RealtimePublisher<std_msgs::Empty>(name + "/calibrated", 1);
+ pub_calibrated_ = new realtime_tools::RealtimePublisher<std_msgs::Empty>(name + "/calibrated", 1);
return true;
}
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -46,7 +46,7 @@
#include <ros/node.h>
#include <math.h>
#include <robot_msgs/DiagnosticMessage.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <mechanism_model/controller.h>
#include <control_toolbox/sine_sweep.h>
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -48,7 +48,7 @@
#include <ros/node.h>
#include <math.h>
#include <robot_msgs/DiagnosticMessage.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <mechanism_model/controller.h>
#include <robot_mechanism_controllers/joint_velocity_controller.h>
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/sine_sweep_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/sine_sweep_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/sine_sweep_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -46,7 +46,7 @@
#include <ros/node.h>
#include <math.h>
#include <robot_msgs/DiagnosticMessage.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <mechanism_model/controller.h>
#include <control_toolbox/sine_sweep.h>
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -8,7 +8,7 @@
<depend package="wg_robot_description_parser" />
<depend package="stl_utils" />
<depend package="newmat10" />
- <depend package="misc_utils" />
+ <depend package="realtime_tools" />
<depend package="robot_msgs" />
<depend package="robot_mechanism_controllers" />
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_orientation_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_orientation_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_orientation_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -52,7 +52,7 @@
#include "mechanism_model/controller.h"
#include "tf/tf.h"
#include "tf/transform_listener.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "misc_utils/advertised_service_guard.h"
#include "misc_utils/subscription_guard.h"
@@ -102,7 +102,7 @@
SubscriptionGuard guard_set_command_;
std_msgs::QuaternionStamped command_msg_;
- misc_utils::RealtimePublisher<std_msgs::QuaternionStamped> *pos_publisher_;
+ realtime_tools::RealtimePublisher<std_msgs::QuaternionStamped> *pos_publisher_;
tf::TransformListener TF;
int loop_count_;
};
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_position_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_position_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_position_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -53,7 +53,7 @@
#include "mechanism_model/controller.h"
#include "tf/tf.h"
#include "tf/transform_listener.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "misc_utils/advertised_service_guard.h"
#include "misc_utils/subscription_guard.h"
@@ -103,7 +103,7 @@
SubscriptionGuard guard_set_command_;
std_msgs::PointStamped command_msg_;
- misc_utils::RealtimePublisher<std_msgs::PointStamped> *pos_publisher_;
+ realtime_tools::RealtimePublisher<std_msgs::PointStamped> *pos_publisher_;
tf::TransformListener TF;
int loop_count_;
};
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_velocity_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_velocity_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_velocity_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -54,8 +54,8 @@
#include "tf/transform_datatypes.h"
#include "misc_utils/advertised_service_guard.h"
#include "misc_utils/subscription_guard.h"
-#include "misc_utils/realtime_publisher.h"
-#include "misc_utils/realtime_infuser.h"
+#include "realtime_tools/realtime_publisher.h"
+#include "realtime_tools/realtime_infuser.h"
namespace controller {
@@ -69,7 +69,7 @@
void update();
//tf::Vector3 command_;
- misc_utils::RealtimeInfuser<tf::Vector3> command_;
+ realtime_tools::RealtimeInfuser<tf::Vector3> command_;
void getTipVelocity(tf::Vector3 *v);
private:
@@ -102,7 +102,7 @@
std_msgs::Vector3 command_msg_;
- misc_utils::RealtimePublisher<std_msgs::Vector3> *vel_publisher_;
+ realtime_tools::RealtimePublisher<std_msgs::Vector3> *vel_publisher_;
int loop_count_;
};
Modified: 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_calibration_controller.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/joint_calibration_controller.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -60,7 +60,7 @@
#include "mechanism_model/robot.h"
#include "robot_mechanism_controllers/joint_velocity_controller.h"
-#include "misc_utils/realtime_publisher.h"
+#include "realtime_tools/realtime_publisher.h"
#include "std_msgs/Empty.h"
@@ -115,7 +115,7 @@
JointCalibrationController c_;
double last_publish_time_;
- misc_utils::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
+ realtime_tools::RealtimePublisher<std_msgs::Empty> *pub_calibrated_;
};
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -10,6 +10,7 @@
<depend package="tinyxml" />
<depend package="stl_utils" />
<depend package="misc_utils" />
+ <depend package="realtime_tools" />
<depend package="roscpp" />
<depend package="bullet" />
<depend package="std_msgs" />
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_orientation_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -166,7 +166,7 @@
&CartesianOrientationControllerNode::setCommand, this, 1);
guard_set_command_.set(topic + "/set_command");
- pos_publisher_ = new misc_utils::RealtimePublisher<std_msgs::QuaternionStamped>(topic + "/position", 1);
+ pos_publisher_ = new realtime_tools::RealtimePublisher<std_msgs::QuaternionStamped>(topic + "/position", 1);
return true;
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_position_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -165,8 +165,8 @@
&CartesianPositionControllerNode::setCommand, this, 1);
guard_set_command_.set(topic + "/set_command");
- //pos_publisher_ = new misc_utils::RealtimePublisher<std_msgs::Vector3>(topic + "/position", 0);
- pos_publisher_ = new misc_utils::RealtimePublisher<std_msgs::PointStamped>(topic + "/position", 1);
+ //pos_publisher_ = new realtime_tools::RealtimePublisher<std_msgs::Vector3>(topic + "/position", 0);
+ pos_publisher_ = new realtime_tools::RealtimePublisher<std_msgs::PointStamped>(topic + "/position", 1);
return true;
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_velocity_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_velocity_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_velocity_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -143,7 +143,7 @@
&CartesianVelocityControllerNode::command, this, 1);
guard_command_.set(topic + "/command");
- vel_publisher_ = new misc_utils::RealtimePublisher<std_msgs::Vector3>(topic + "/velocity", 0);
+ vel_publisher_ = new realtime_tools::RealtimePublisher<std_msgs::Vector3>(topic + "/velocity", 0);
return true;
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_calibration_controller.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -217,7 +217,7 @@
if (!c_.initXml(robot, config))
return false;
- pub_calibrated_ = new misc_utils::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
+ pub_calibrated_ = new realtime_tools::RealtimePublisher<std_msgs::Empty>(topic + "/calibrated", 1);
return true;
}
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -45,7 +45,7 @@
#include "ethercat_hardware/ethercat_device.h"
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
class EthercatHardware
{
@@ -101,7 +101,7 @@
bool halt_motors_;
unsigned int reset_state_;
- misc_utils::RealtimePublisher<robot_msgs::DiagnosticMessage> publisher_;
+ realtime_tools::RealtimePublisher<robot_msgs::DiagnosticMessage> publisher_;
struct {
struct {
double roundtrip_;
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -37,7 +37,7 @@
#include <ethercat_hardware/ethercat_device.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <ethercat_hardware/PressureState.h>
struct WG0XMbxHdr
@@ -324,7 +324,7 @@
};
private:
uint32_t last_pressure_time_;
- misc_utils::RealtimePublisher<ethercat_hardware::PressureState> publisher_;
+ realtime_tools::RealtimePublisher<ethercat_hardware::PressureState> publisher_;
};
#endif /* WG0X_H */
Modified: pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -11,7 +11,7 @@
<depend package='tinyxml'/>
<depend package='roscpp' />
<depend package='loki' />
-<depend package='misc_utils' />
+<depend package='realtime_tools' />
<depend package='robot_msgs' />
<depend package='xenomai' />
<depend package='boost' />
Modified: pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
===================================================================
--- pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -43,7 +43,7 @@
#include <mechanism_model/robot.h>
#include <boost/thread/mutex.hpp>
#include <mechanism_model/controller.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
#include <misc_utils/advertised_service_guard.h>
#include <robot_srvs/ListControllerTypes.h>
@@ -127,9 +127,9 @@
int cycles_since_publish_;
const char* const mechanism_state_topic_;
- misc_utils::RealtimePublisher<robot_msgs::MechanismState> publisher_;
+ realtime_tools::RealtimePublisher<robot_msgs::MechanismState> publisher_;
- misc_utils::RealtimePublisher<tf::tfMessage> transform_publisher_;
+ realtime_tools::RealtimePublisher<tf::tfMessage> transform_publisher_;
AdvertisedServiceGuard list_controllers_guard_, list_controller_types_guard_,
spawn_controller_guard_, kill_controller_guard_;
Modified: pkg/trunk/mechanism/mechanism_control/manifest.xml
===================================================================
--- pkg/trunk/mechanism/mechanism_control/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/mechanism/mechanism_control/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -11,6 +11,7 @@
<depend package="tinyxml"/>
<depend package="mechanism_model"/>
<depend package="misc_utils" />
+<depend package="realtime_tools" />
<depend package="rospy" />
<depend package="tf" />
<depend package="robot_msgs" />
Modified: pkg/trunk/robot_control_loops/pr2_etherCAT/manifest.xml
===================================================================
--- pkg/trunk/robot_control_loops/pr2_etherCAT/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/robot_control_loops/pr2_etherCAT/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -13,6 +13,7 @@
<depend package="robot_mechanism_controllers"/>
<depend package="pr2_mechanism_controllers"/>
<depend package="joint_qualification_controllers"/>
+ <depend package="realtime_tools"/>
<depend package="xenomai"/>
<url>http://pr.willowgarage.com</url>
<repository>http://pr.willowgarage.com/repos</repository>
Modified: pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp
===================================================================
--- pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/robot_control_loops/pr2_etherCAT/src/main.cpp 2009-01-18 18:49:35 UTC (rev 9673)
@@ -51,7 +51,7 @@
#include <ros/node.h>
#include <std_srvs/Empty.h>
-#include <misc_utils/realtime_publisher.h>
+#include <realtime_tools/realtime_publisher.h>
static struct
{
@@ -94,7 +94,7 @@
int secondary;
} diagnostics;
-static void publishDiagnostics(misc_utils::RealtimePublisher<robot_msgs::DiagnosticMessage> &publisher)
+static void publishDiagnostics(realtime_tools::RealtimePublisher<robot_msgs::DiagnosticMessage> &publisher)
{
if (publisher.trylock())
{
@@ -166,7 +166,7 @@
void controlLoop(void *)
{
- misc_utils::RealtimePublisher<robot_msgs::DiagnosticMessage> publisher("/diagnostics", 2);
+ realtime_tools::RealtimePublisher<robot_msgs::DiagnosticMessage> publisher("/diagnostics", 2);
// Publish one-time before entering real-time to pre-allocate message vectors
publishDiagnostics(publisher);
Deleted: pkg/trunk/util/misc_utils/include/misc_utils/realtime_infuser.h
===================================================================
--- pkg/trunk/util/misc_utils/include/misc_utils/realtime_infuser.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/util/misc_utils/include/misc_utils/realtime_infuser.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -1,98 +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.
- */
-/*
- The RealtimeInfuser allows a non-realtime thread to write to a value
- for the realtime thread to read.
-
- No more than 2 threads are supported: one calling get and another
- calling set.
-
- Author: Stuart Glaser
- */
-#ifndef REALTIME_INFUSER_H
-#define REALTIME_INFUSER_H
-
-namespace misc_utils {
-
-template <class T>
-class RealtimeInfuser
-{
-public:
- RealtimeInfuser(const T &initial = T()) : in_use(0), ready(1)
- {
- set(initial);
- }
-
- // Called from non-realtime.
- void set(const T &value)
- {
- int next_slot = unused();
- data[next_slot] = value;
- ready = next_slot;
- }
-
- // True iff new data is ready.
- bool has_next()
- {
- return in_use != ready;
- }
-
- // Called from realtime. Returns the next available value.
- T& next()
- {
- in_use = ready;
- return data[in_use];
- }
-
-private:
- // Three slots are used to pass data from non-realtime to realtime.
- // The object in the in_use slot is currently being used by the
- // realtime loop. The object in the ready slot has been written by
- // the non-realtime. The last slot is considered unused and is the
- // next place to which the non-realtime thread will write.
- T data[3];
- int in_use, ready;
-
- // Returns the slot in data that is not being used.
- int unused()
- {
- if (0 != in_use && 0 != ready)
- return 0;
- if (1 != in_use && 1 != ready)
- return 1;
- if (2 != in_use && 2 != ready)
- return 2;
- abort();
- }
-
-};
-
-}
-
-#endif
Deleted: pkg/trunk/util/misc_utils/include/misc_utils/realtime_publisher.h
===================================================================
--- pkg/trunk/util/misc_utils/include/misc_utils/realtime_publisher.h 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/util/misc_utils/include/misc_utils/realtime_publisher.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -1,192 +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.
- */
-
-/*
- * Publishing ROS messages is difficult, as the publish function is
- * not realtime safe. This class provides the proper locking so that
- * you can call publish in realtime and a separate (non-realtime)
- * thread will ensure that the message gets published over ROS.
- *
- * Author: Stuart Glaser
- */
-#ifndef REALTIME_PUBLISHER_H
-#define REALTIME_PUBLISHER_H
-
-#include <string>
-#include <ros/node.h>
-#include <boost/thread/mutex.hpp>
-#include <boost/thread/thread.hpp>
-#include <realtime_tools/realtime_tools.h>
-
-namespace misc_utils {
-
-template <class Msg>
-class RealtimePublisher
-{
-public:
- RealtimePublisher(const std::string &topic, int queue_size)
- : topic_(topic), node_(NULL), is_running_(false), keep_running_(false), turn_(REALTIME)
- {
- if ((node_ = ros::Node::instance()) == NULL)
- {
- int argc = 0; char **argv = NULL;
- ros::init(argc, argv);
- node_ = new ros::Node("realtime_publisher", ros::Node::DONT_HANDLE_SIGINT);
- }
-
- node_->advertise<Msg>(topic_, queue_size);
-
- if (0 != realtime_cond_create(&updated_cond_))
- {
- perror("realtime_cond_create");
- abort();
- }
- if (0 != realtime_mutex_create(&msg_lock_))
- {
- perror("realtime_mutex_create");
- abort();
- }
- keep_running_ = true;
- thread_ = boost::thread(&RealtimePublisher::publishingLoop, this);
- }
-
- ~RealtimePublisher()
- {
- stop();
- while (is_running())
- usleep(100);
-
- // TODO: fix when multiple nodes per process are supported
-
- // Don't unadvertise topic because other threads within the
- // process may still be publishing on the topic
- //node_->unadvertise(topic_);
-
- // Destroy thread resources
- realtime_cond_delete(&updated_cond_);
- realtime_mutex_delete(&msg_lock_);
- }
-
- void stop()
- {
- keep_running_ = false;
- realtime_cond_signal(&updated_cond_); // So the publishing loop can exit
- }
-
- Msg msg_;
-
- int lock()
- {
- return realtime_mutex_lock(&msg_lock_);
- }
-
- bool trylock()
- {
- if (0 == realtime_mutex_trylock(&msg_lock_))
- {
- if (turn_ == REALTIME)
- {
- return true;
- }
- else
- {
- realtime_mutex_unlock(&msg_lock_);
- return false;
- }
- }
- else
- return false;
- }
-
- void unlock()
- {
- realtime_mutex_unlock(&msg_lock_);
- }
-
- void unlockAndPublish()
- {
- turn_ = NON_REALTIME;
- realtime_mutex_unlock(&msg_lock_);
- realtime_cond_signal(&updated_cond_);
- }
-
- bool is_running() const { return is_running_; }
-
- void publishingLoop()
- {
- RealtimeTask task;
-
- int err = realtime_shadow_task(&task);
- if (err)
- ROS_WARN("Unable to shadow task: %d\n", err);
-
- is_running_ = true;
- turn_ = REALTIME;
- while (keep_running_)
- {
- // Locks msg_ and copies it
- realtime_mutex_lock(&msg_lock_);
- while (turn_ != NON_REALTIME)
- {
- if (!keep_running_)
- break;
- realtime_cond_wait(&updated_cond_, &msg_lock_);
- }
-
- Msg outgoing(msg_);
- turn_ = REALTIME;
- realtime_mutex_unlock(&msg_lock_);
-
- // Sends the outgoing message
- if (keep_running_)
- node_->publish(topic_, outgoing);
- }
- is_running_ = false;
- }
-
- std::string topic_;
-
-private:
-
- ros::Node *node_;
- bool is_running_;
- bool keep_running_;
-
- boost::thread thread_;
-
- RealtimeMutex msg_lock_; // Protects msg_
- RealtimeCond updated_cond_;
-
- enum {REALTIME, NON_REALTIME};
- int turn_; // Who's turn is it to use msg_?
-};
-
-}
-
-#endif
Modified: pkg/trunk/util/misc_utils/manifest.xml
===================================================================
--- pkg/trunk/util/misc_utils/manifest.xml 2009-01-18 18:26:39 UTC (rev 9672)
+++ pkg/trunk/util/misc_utils/manifest.xml 2009-01-18 18:49:35 UTC (rev 9673)
@@ -9,7 +9,6 @@
<review status="unreviewed" notes="API review in progress (Stu)"/>
<url>http://pr.willowgarage.com</url>
<depend package="roscpp" />
- <depend package="realtime_tools" />
<depend package="boost" />
<export>
<cpp cflags="-I${prefix}/include" />
Copied: pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_infuser.h (from rev 9671, pkg/trunk/util/misc_utils/include/misc_utils/realtime_infuser.h)
===================================================================
--- pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_infuser.h (rev 0)
+++ pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_infuser.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -0,0 +1,98 @@
+/*
+ * 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.
+ */
+/*
+ The RealtimeInfuser allows a non-realtime thread to write to a value
+ for the realtime thread to read.
+
+ No more than 2 threads are supported: one calling get and another
+ calling set.
+
+ Author: Stuart Glaser
+ */
+#ifndef REALTIME_INFUSER_H
+#define REALTIME_INFUSER_H
+
+namespace realtime_tools {
+
+template <class T>
+class RealtimeInfuser
+{
+public:
+ RealtimeInfuser(const T &initial = T()) : in_use(0), ready(1)
+ {
+ set(initial);
+ }
+
+ // Called from non-realtime.
+ void set(const T &value)
+ {
+ int next_slot = unused();
+ data[next_slot] = value;
+ ready = next_slot;
+ }
+
+ // True iff new data is ready.
+ bool has_next()
+ {
+ return in_use != ready;
+ }
+
+ // Called from realtime. Returns the next available value.
+ T& next()
+ {
+ in_use = ready;
+ return data[in_use];
+ }
+
+private:
+ // Three slots are used to pass data from non-realtime to realtime.
+ // The object in the in_use slot is currently being used by the
+ // realtime loop. The object in the ready slot has been written by
+ // the non-realtime. The last slot is considered unused and is the
+ // next place to which the non-realtime thread will write.
+ T data[3];
+ int in_use, ready;
+
+ // Returns the slot in data that is not being used.
+ int unused()
+ {
+ if (0 != in_use && 0 != ready)
+ return 0;
+ if (1 != in_use && 1 != ready)
+ return 1;
+ if (2 != in_use && 2 != ready)
+ return 2;
+ abort();
+ }
+
+};
+
+}
+
+#endif
Copied: pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_publisher.h (from rev 9672, pkg/trunk/util/misc_utils/include/misc_utils/realtime_publisher.h)
===================================================================
--- pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_publisher.h (rev 0)
+++ pkg/trunk/util/realtime_tools/include/realtime_tools/realtime_publisher.h 2009-01-18 18:49:35 UTC (rev 9673)
@@ -0,0 +1,192 @@
+/*
+ * 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 ...
[truncated message content] |