|
From: <mee...@us...> - 2009-05-15 18:26:16
|
Revision: 15529
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=15529&view=rev
Author: meeussen
Date: 2009-05-15 18:26:07 +0000 (Fri, 15 May 2009)
Log Message:
-----------
move laser trajectory messages/services to pr2_msgs pr2_srvs
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp
pkg/trunk/highlevel/pr2_robot_actions/src/set_laser_tilt.cpp
Added Paths:
-----------
pkg/trunk/pr2_msgs/msg/LaserTrajCmd.msg
pkg/trunk/pr2_srvs/srv/SetLaserTrajCmd.srv
Removed Paths:
-------------
pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserTrajCmd.msg
pkg/trunk/controllers/pr2_mechanism_controllers/srv/SetLaserTrajCmd.srv
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-05-15 18:10:16 UTC (rev 15528)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/laser_scanner_traj_controller.h 2009-05-15 18:26:07 UTC (rev 15529)
@@ -48,14 +48,14 @@
#include <pr2_mechanism_controllers/LaserScannerSignal.h>
#include <pr2_msgs/PeriodicCmd.h>
#include <pr2_mechanism_controllers/TrackLinkCmd.h>
-#include <pr2_mechanism_controllers/LaserTrajCmd.h>
+#include <pr2_msgs/LaserTrajCmd.h>
// Services
#include <robot_mechanism_controllers/SetCommand.h>
#include <robot_mechanism_controllers/GetCommand.h>
#include <pr2_mechanism_controllers/SetProfile.h>
#include <pr2_srvs/SetPeriodicCmd.h>
-#include <pr2_mechanism_controllers/SetLaserTrajCmd.h>
+#include <pr2_srvs/SetLaserTrajCmd.h>
#include "boost/thread/mutex.hpp"
#include "trajectory/trajectory.h"
@@ -75,7 +75,7 @@
bool setPeriodicCmd(const pr2_msgs::PeriodicCmd& cmd) ;
- bool setTrajCmd(const pr2_mechanism_controllers::LaserTrajCmd& traj_cmd) ;
+ bool setTrajCmd(const pr2_msgs::LaserTrajCmd& traj_cmd) ;
bool setTrackLinkCmd(const pr2_mechanism_controllers::TrackLinkCmd& track_link_cmd) ;
@@ -139,8 +139,8 @@
void setTrackLinkCmd() ;
bool setPeriodicSrv(pr2_srvs::SetPeriodicCmd::Request &req,
pr2_srvs::SetPeriodicCmd::Response &res);
- bool setTrajSrv(pr2_mechanism_controllers::SetLaserTrajCmd::Request &req,
- pr2_mechanism_controllers::SetLaserTrajCmd::Response &res);
+ bool setTrajSrv(pr2_srvs::SetLaserTrajCmd::Request &req,
+ pr2_srvs::SetLaserTrajCmd::Response &res);
private:
@@ -152,7 +152,7 @@
double prev_profile_time_ ; //!< The time in the current profile when update() was last called
pr2_msgs::PeriodicCmd cmd_ ;
- pr2_mechanism_controllers::LaserTrajCmd traj_cmd_ ;
+ 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
Deleted: pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserTrajCmd.msg
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserTrajCmd.msg 2009-05-15 18:10:16 UTC (rev 15528)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserTrajCmd.msg 2009-05-15 18:26:07 UTC (rev 15529)
@@ -1,6 +0,0 @@
-Header header
-string profile # options are currently "linear" or "linear_blended"
-float64[] pos # Laser positions
-float64[] time # Times to reach laser positions in seconds
-float64 max_rate # Set to -1 to use default
-float64 max_accel # Set to -1 to use default
\ No newline at end of file
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-05-15 18:10:16 UTC (rev 15528)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/laser_scanner_traj_controller.cpp 2009-05-15 18:26:07 UTC (rev 15529)
@@ -297,7 +297,7 @@
}
}
-bool LaserScannerTrajController::setTrajCmd(const pr2_mechanism_controllers::LaserTrajCmd& traj_cmd)
+bool LaserScannerTrajController::setTrajCmd(const pr2_msgs::LaserTrajCmd& traj_cmd)
{
if (traj_cmd.profile == "linear" ||
traj_cmd.profile == "blended_linear")
@@ -500,8 +500,8 @@
c_.setPeriodicCmd(cmd_) ;
}
-bool LaserScannerTrajControllerNode::setTrajSrv(pr2_mechanism_controllers::SetLaserTrajCmd::Request &req,
- pr2_mechanism_controllers::SetLaserTrajCmd::Response &res)
+bool LaserScannerTrajControllerNode::setTrajSrv(pr2_srvs::SetLaserTrajCmd::Request &req,
+ pr2_srvs::SetLaserTrajCmd::Response &res)
{
ROS_INFO("LaserScannerTrajControllerNode: set traj command");
Deleted: pkg/trunk/controllers/pr2_mechanism_controllers/srv/SetLaserTrajCmd.srv
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/srv/SetLaserTrajCmd.srv 2009-05-15 18:10:16 UTC (rev 15528)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/srv/SetLaserTrajCmd.srv 2009-05-15 18:26:07 UTC (rev 15529)
@@ -1,3 +0,0 @@
-LaserTrajCmd command
----
-time start_time
\ No newline at end of file
Modified: pkg/trunk/highlevel/pr2_robot_actions/src/set_laser_tilt.cpp
===================================================================
--- pkg/trunk/highlevel/pr2_robot_actions/src/set_laser_tilt.cpp 2009-05-15 18:10:16 UTC (rev 15528)
+++ pkg/trunk/highlevel/pr2_robot_actions/src/set_laser_tilt.cpp 2009-05-15 18:26:07 UTC (rev 15529)
@@ -36,42 +36,47 @@
*********************************************************************/
#include <robot_actions/action.h>
#include <robot_actions/action_runner.h>
-#include <pr2_srvs/SetPeriodicCmd.h>
-#include <pr2_msgs/PeriodicCmd.h>
+#include <pr2_msgs/LaserTrajCmd.h>
+#include <pr2_srvs/SetLaserTrajCmd.h>
#include <pr2_robot_actions/SetLaserTiltState.h>
+#include <std_msgs/Empty.h>
+#include <robot_actions/NoArgumentsActionState.h>
#include <string>
#include <ros/ros.h>
namespace pr2_robot_actions {
- class SetLaserTilt : public robot_actions::Action<pr2_msgs::PeriodicCmd, pr2_msgs::PeriodicCmd> {
- public:
- SetLaserTilt(std::string laser_controller): robot_actions::Action<pr2_msgs::PeriodicCmd, pr2_msgs::PeriodicCmd>("set_laser_tilt"),
- laser_controller_(laser_controller){}
+ class SetLaserTilt : public robot_actions::Action<std_msgs::Empty, std_msgs::Empty> {
+ public:
+ SetLaserTilt(std::string laser_controller): robot_actions::Action<std_msgs::Empty, std_msgs::Empty>("set_laser_tilt"),
+ laser_controller_(laser_controller){}
- robot_actions::ResultStatus execute(const pr2_msgs::PeriodicCmd& goal, pr2_msgs::PeriodicCmd& feedback){
- pr2_srvs::SetPeriodicCmd::Request req_laser;
- pr2_srvs::SetPeriodicCmd::Response res_laser;
- req_laser.command = goal;
-
- if(!ros::service::call(laser_controller_ + "/set_periodic_cmd", req_laser, res_laser)){
- ROS_ERROR("Failed to start laser.");
- return robot_actions::ABORTED;
- }
-
- return robot_actions::SUCCESS;
-
+ robot_actions::ResultStatus execute(const std_msgs::Empty& empty, std_msgs::Empty& feedback){
+ pr2_srvs::SetLaserTrajCmd::Request req_laser;
+ pr2_srvs::SetLaserTrajCmd::Response res_laser;
+ req_laser.command.profile = "linear";
+ req_laser.command.max_rate = 5;
+ req_laser.command.max_accel = 5;
+ req_laser.command.pos.push_back(1.0); req_laser.command.pos.push_back(-0.7); req_laser.command.pos.push_back(1.0);
+ req_laser.command.time.push_back(0.0); req_laser.command.time.push_back(1.8); req_laser.command.time.push_back(2.025);
+ if(!ros::service::call(laser_controller_ + "/set_periodic_cmd", req_laser, res_laser)){
+ ROS_ERROR("Failed to start laser.");
+ return robot_actions::ABORTED;
}
-
- private:
- std::string laser_controller_;
+
+ return robot_actions::SUCCESS;
+
+ }
+
+ private:
+ std::string laser_controller_;
};
-
+
};
int main(int argc, char** argv){
ros::init(argc, argv, "set_laser_tilt");
pr2_robot_actions::SetLaserTilt setter("laser_tilt_controller");
robot_actions::ActionRunner runner(20.0);
- runner.connect<pr2_msgs::PeriodicCmd, pr2_robot_actions::SetLaserTiltState, pr2_msgs::PeriodicCmd>(setter);
+ runner.connect<std_msgs::Empty, robot_actions::NoArgumentsActionState, std_msgs::Empty>(setter);
runner.run();
ros::spin();
Copied: pkg/trunk/pr2_msgs/msg/LaserTrajCmd.msg (from rev 15517, pkg/trunk/controllers/pr2_mechanism_controllers/msg/LaserTrajCmd.msg)
===================================================================
--- pkg/trunk/pr2_msgs/msg/LaserTrajCmd.msg (rev 0)
+++ pkg/trunk/pr2_msgs/msg/LaserTrajCmd.msg 2009-05-15 18:26:07 UTC (rev 15529)
@@ -0,0 +1,6 @@
+Header header
+string profile # options are currently "linear" or "linear_blended"
+float64[] pos # Laser positions
+float64[] time # Times to reach laser positions in seconds
+float64 max_rate # Set to -1 to use default
+float64 max_accel # Set to -1 to use default
\ No newline at end of file
Copied: pkg/trunk/pr2_srvs/srv/SetLaserTrajCmd.srv (from rev 15517, pkg/trunk/controllers/pr2_mechanism_controllers/srv/SetLaserTrajCmd.srv)
===================================================================
--- pkg/trunk/pr2_srvs/srv/SetLaserTrajCmd.srv (rev 0)
+++ pkg/trunk/pr2_srvs/srv/SetLaserTrajCmd.srv 2009-05-15 18:26:07 UTC (rev 15529)
@@ -0,0 +1,3 @@
+pr2_msgs/LaserTrajCmd command
+---
+time start_time
\ No newline at end of file
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|