|
From: <vij...@us...> - 2009-06-30 21:52:31
|
Revision: 18006
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=18006&view=rev
Author: vijaypradeep
Date: 2009-06-30 21:52:25 +0000 (Tue, 30 Jun 2009)
Log Message:
-----------
Moving LaserScannerSignal to pr2_msgs. PointCloud assembler no longer depends on pr2_mechanism_controllers
Modified Paths:
--------------
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/src/laser_scanner_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/manifest.xml
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_snapshotter.cpp
pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_srv.cpp
Added Paths:
-----------
pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/LaserScannerSignal.msg
Removed Paths:
-------------
pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserScannerSignal.msg
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-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_controller.h 2009-06-30 21:52:25 UTC (rev 18006)
@@ -42,7 +42,7 @@
#include <realtime_tools/realtime_publisher.h>
// Messages
-#include <pr2_mechanism_controllers/LaserScannerSignal.h>
+#include <pr2_msgs/LaserScannerSignal.h>
// Services
#include <robot_mechanism_controllers/SetCommand.h>
@@ -258,9 +258,9 @@
bool first_time_ ;
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
+ pr2_msgs::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.
- realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_msgs::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-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h 2009-06-30 21:52:25 UTC (rev 18006)
@@ -45,7 +45,7 @@
#include "filters/transfer_function.h"
// Messages
-#include <pr2_mechanism_controllers/LaserScannerSignal.h>
+#include <pr2_msgs/LaserScannerSignal.h>
#include <pr2_msgs/PeriodicCmd.h>
#include <pr2_mechanism_controllers/TrackLinkCmd.h>
#include <pr2_msgs/LaserTrajCmd.h>
@@ -155,9 +155,9 @@
pr2_msgs::LaserTrajCmd traj_cmd_ ;
pr2_mechanism_controllers::TrackLinkCmd track_link_cmd_ ;
- 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
+ pr2_msgs::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.
- realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
+ realtime_tools::RealtimePublisher <pr2_msgs::LaserScannerSignal>* publisher_ ; //!< Publishes the m_scanner_signal msg from the update() realtime loop
};
}
Deleted: pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserScannerSignal.msg
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserScannerSignal.msg 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserScannerSignal.msg 2009-06-30 21:52:25 UTC (rev 18006)
@@ -1,7 +0,0 @@
-
-
-Header header
-
-# signal == 0 => Half profile complete
-# signal == 1 => Full Profile Complete
-int32 signal
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_controller.cpp 2009-06-30 21:52:25 UTC (rev 18006)
@@ -573,7 +573,7 @@
if (publisher_ != NULL) // Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <pr2_msgs::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-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-06-30 21:52:25 UTC (rev 18006)
@@ -489,7 +489,7 @@
if (publisher_ != NULL) // Make sure that we don't memory leak if initXml gets called twice
delete publisher_ ;
- publisher_ = new realtime_tools::RealtimePublisher <pr2_mechanism_controllers::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
+ publisher_ = new realtime_tools::RealtimePublisher <pr2_msgs::LaserScannerSignal> (service_prefix_ + "/laser_scanner_signal", 1) ;
prev_profile_time_ = 0.0 ;
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/manifest.xml 2009-06-30 21:52:25 UTC (rev 18006)
@@ -15,7 +15,7 @@
<depend package="robot_msgs"/>
<depend package="mechanism_msgs" />
<depend package="sensor_msgs"/>
- <depend package="pr2_mechanism_controllers"/>
+ <depend package="pr2_msgs"/>
<depend package="image_msgs" />
<depend package="mechanism_msgs" />
<depend package="message_filters" />
Modified: pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/drivers/robot/pr2/dense_laser_assembler/src/dense_laser_snapshotter.cpp 2009-06-30 21:52:25 UTC (rev 18006)
@@ -39,7 +39,7 @@
// Messages
#include "calibration_msgs/DenseLaserSnapshot.h"
-#include "pr2_mechanism_controllers/LaserScannerSignal.h"
+#include "pr2_msgs/LaserScannerSignal.h"
using namespace dense_laser_assembler ;
@@ -64,7 +64,7 @@
}
- void scannerSignalCallback(const pr2_mechanism_controllers::LaserScannerSignalConstPtr& cur_signal)
+ void scannerSignalCallback(const pr2_msgs::LaserScannerSignalConstPtr& cur_signal)
{
if (cur_signal->signal == 128 || cur_signal->signal == 129) // These codes imply that this is the first signal during a given profile type
first_time_ = true ;
@@ -117,7 +117,7 @@
ros::Subscriber signal_sub_ ;
ros::Publisher snapshot_pub_ ;
- pr2_mechanism_controllers::LaserScannerSignal prev_signal_;
+ pr2_msgs::LaserScannerSignal prev_signal_;
bool first_time_ ;
} ;
Modified: pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/manifest.xml
===================================================================
--- pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/manifest.xml 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/manifest.xml 2009-06-30 21:52:25 UTC (rev 18006)
@@ -13,7 +13,7 @@
<depend package="sensor_msgs"/>
<depend package="tf"/>
<depend package="pr2_srvs"/>
- <depend package="pr2_mechanism_controllers"/>
+ <depend package="pr2_msgs"/>
# For Testing
<depend package="rostest"/>
<depend package="gtest"/>
Modified: pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_snapshotter.cpp
===================================================================
--- pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_snapshotter.cpp 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_snapshotter.cpp 2009-06-30 21:52:25 UTC (rev 18006)
@@ -39,7 +39,7 @@
// Messages
#include "robot_msgs/PointCloud.h"
-#include "pr2_mechanism_controllers/LaserScannerSignal.h"
+#include "pr2_msgs/LaserScannerSignal.h"
using namespace robot_msgs ;
@@ -58,8 +58,8 @@
public:
- pr2_mechanism_controllers::LaserScannerSignal prev_signal_;
- pr2_mechanism_controllers::LaserScannerSignal cur_signal_;
+ pr2_msgs::LaserScannerSignal prev_signal_;
+ pr2_msgs::LaserScannerSignal cur_signal_;
bool first_time_ ;
Modified: pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_srv.cpp
===================================================================
--- pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_srv.cpp 2009-06-30 21:51:46 UTC (rev 18005)
+++ pkg/trunk/stacks/pr2_drivers/point_cloud_assembler/src/point_cloud_srv.cpp 2009-06-30 21:52:25 UTC (rev 18006)
@@ -40,7 +40,7 @@
// Messages
#include "robot_msgs/PointCloud.h"
-#include "pr2_mechanism_controllers/LaserScannerSignal.h"
+#include "pr2_msgs/LaserScannerSignal.h"
#include <boost/thread/mutex.hpp>
@@ -63,7 +63,7 @@
class PointCloudSrv : public ros::Node
{
private:
- pr2_mechanism_controllers::LaserScannerSignal laser_scanner_signal_;
+ pr2_msgs::LaserScannerSignal laser_scanner_signal_;
ros::Time laser_time_;
boost::mutex laser_mutex_;
Copied: pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/LaserScannerSignal.msg (from rev 18005, pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserScannerSignal.msg)
===================================================================
--- pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/LaserScannerSignal.msg (rev 0)
+++ pkg/trunk/stacks/pr2_drivers/pr2_msgs/msg/LaserScannerSignal.msg 2009-06-30 21:52:25 UTC (rev 18006)
@@ -0,0 +1,7 @@
+
+
+Header header
+
+# signal == 0 => Half profile complete
+# signal == 1 => Full Profile Complete
+int32 signal
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|