|
From: <tpr...@us...> - 2009-04-24 23:04:49
|
Revision: 14422
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=14422&view=rev
Author: tpratkanis
Date: 2009-04-24 23:04:40 +0000 (Fri, 24 Apr 2009)
Log Message:
-----------
Huge change to robot_actions. See ros users.
Modified Paths:
--------------
pkg/trunk/deprecated/highlevel_controllers/include/highlevel_controllers/move_base.hh
pkg/trunk/deprecated/highlevel_controllers/manifest.xml
pkg/trunk/deprecated/highlevel_controllers/src/action_container.cpp
pkg/trunk/deprecated/highlevel_controllers/src/move_base.cpp
pkg/trunk/deprecated/highlevel_controllers/src/recharge_controller.cpp
pkg/trunk/highlevel/doors/doors_core/include/doors_core/door_reactive_planner.h
pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h
pkg/trunk/highlevel/doors/doors_core/manifest.xml
pkg/trunk/highlevel/doors/doors_core/src/action_runner.cpp
pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp
pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_detector.cpp
pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_opener.cpp
pkg/trunk/highlevel/doors/doors_core/test/trigger_handle_release.cpp
pkg/trunk/highlevel/executive_python/manifest.xml
pkg/trunk/highlevel/executive_python/src/navigation_adapter.py
pkg/trunk/highlevel/executive_python/src/recharge_adapter.py
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapter_utilities.h
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapters.h
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/adapters.cc
pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/stub_ros_container.cc
pkg/trunk/highlevel/nav/include/nav/move_base.h
pkg/trunk/highlevel/nav/include/nav/move_base_local.h
pkg/trunk/highlevel/nav/manifest.xml
pkg/trunk/highlevel/nav/src/move_base.cpp
pkg/trunk/highlevel/nav/src/move_base_local.cpp
pkg/trunk/highlevel/plugs/plugs_core/include/plugs_core/action_detect_outlet_fine.h
pkg/trunk/highlevel/plugs/plugs_core/manifest.xml
pkg/trunk/highlevel/plugs/plugs_core/src/action_runner.cpp
pkg/trunk/highlevel/plugs/plugs_core/test/test_executive.cpp
pkg/trunk/highlevel/robot_actions/CMakeLists.txt
pkg/trunk/highlevel/robot_actions/manifest.xml
pkg/trunk/highlevel/safety/safety_core/manifest.xml
pkg/trunk/highlevel/safety/safety_core/src/action_runner.cpp
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/action_mechanism_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/mechanism/mechanism_control/src/action_mechanism_control.cpp
pkg/trunk/mechanism/mechanism_control/src/action_runner.cpp
pkg/trunk/mechanism/mechanism_control/test/action_runner_test.cpp
pkg/trunk/nav/people_aware_nav/src/lanes.lisp
pkg/trunk/nav/visual_nav/manifest.xml
pkg/trunk/nav/visual_nav/src/ros_visual_nav.cpp
pkg/trunk/nav/wavefront/manifest.xml
pkg/trunk/nav/wavefront/src/cli.cpp
pkg/trunk/nav/wavefront/src/wavefront_node.cpp
pkg/trunk/vision/outlet_detection/manifest.xml
pkg/trunk/vision/outlet_detection/src/outlet_spotting.cpp
pkg/trunk/vision/people/manifest.xml
pkg/trunk/vision/people/src/people_follower.cpp
pkg/trunk/vision/people/src/people_follower.h
Added Paths:
-----------
pkg/trunk/highlevel/pr2_robot_actions/
pkg/trunk/highlevel/pr2_robot_actions/CMakeLists.txt
pkg/trunk/highlevel/pr2_robot_actions/Makefile
pkg/trunk/highlevel/pr2_robot_actions/manifest.xml
pkg/trunk/highlevel/pr2_robot_actions/msg/
pkg/trunk/highlevel/pr2_robot_actions/msg/CheckPathState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/DetectOutletState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/DetectPlugOnBaseState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/DoorActionState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/LocalizePlugInGripperState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveAndGraspPlugState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveBaseDoorState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveBaseState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveBaseStateNew.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/NoArgumentsActionState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/NotifyDoorBlockedState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/Pose2D.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/RechargeState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/ShellCommandState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/StowPlugState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/SwitchControllers.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/SwitchControllersState.msg
pkg/trunk/highlevel/robot_actions/msg/
pkg/trunk/highlevel/test_robot_actions/
pkg/trunk/highlevel/test_robot_actions/CMakeLists.txt
pkg/trunk/highlevel/test_robot_actions/Makefile
pkg/trunk/highlevel/test_robot_actions/manifest.xml
pkg/trunk/highlevel/test_robot_actions/msg/
pkg/trunk/highlevel/test_robot_actions/msg/TestState.msg
pkg/trunk/highlevel/test_robot_actions/test/
pkg/trunk/highlevel/test_robot_actions/test/test.xml
pkg/trunk/highlevel/test_robot_actions/test/utest.cc
Removed Paths:
-------------
pkg/trunk/highlevel/pr2_robot_actions/msg/ActionStatus.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/CheckPathState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/DetectOutletState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/DetectPlugOnBaseState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/DoorActionState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/LocalizePlugInGripperState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveAndGraspPlugState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveBaseDoorState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveBaseState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/MoveBaseStateNew.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/NoArgumentsActionState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/NotifyDoorBlockedState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/Pose2D.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/RechargeState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/ShellCommandState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/StowPlugState.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/SwitchControllers.msg
pkg/trunk/highlevel/pr2_robot_actions/msg/SwitchControllersState.msg
pkg/trunk/highlevel/robot_actions/msg/
pkg/trunk/highlevel/robot_actions/test/
pkg/trunk/highlevel/test_robot_actions/test/test.xml
pkg/trunk/highlevel/test_robot_actions/test/utest.cc
Modified: pkg/trunk/deprecated/highlevel_controllers/include/highlevel_controllers/move_base.hh
===================================================================
--- pkg/trunk/deprecated/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/deprecated/highlevel_controllers/include/highlevel_controllers/move_base.hh 2009-04-24 23:04:40 UTC (rev 14422)
@@ -51,8 +51,8 @@
#include <mpglue/plan.h>
// Message structures used
-#include <robot_actions/MoveBaseState.h>
-#include <robot_actions/Pose2D.h>
+#include <pr2_robot_actions/MoveBaseState.h>
+#include <pr2_robot_actions/Pose2D.h>
#include <robot_msgs/PoseDot.h>
#include <laser_scan/LaserScan.h>
#include <deprecated_msgs/RobotBase2DOdom.h>
@@ -82,7 +82,7 @@
namespace ros {
namespace highlevel_controllers {
- class MoveBase : public HighlevelController<robot_actions::MoveBaseState, robot_actions::Pose2D> {
+ class MoveBase : public HighlevelController<pr2_robot_actions::MoveBaseState, pr2_robot_actions::Pose2D> {
public:
Modified: pkg/trunk/deprecated/highlevel_controllers/manifest.xml
===================================================================
--- pkg/trunk/deprecated/highlevel_controllers/manifest.xml 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/deprecated/highlevel_controllers/manifest.xml 2009-04-24 23:04:40 UTC (rev 14422)
@@ -19,6 +19,7 @@
<depend package="robot_msgs"/>
<depend package="robot_srvs"/>
<depend package="robot_actions"/>
+ <depend package="pr2_robot_actions"/>
<depend package="pr2_mechanism_controllers"/>
<depend package="pr2_msgs"/>
<depend package="trajectory_rollout"/>
Modified: pkg/trunk/deprecated/highlevel_controllers/src/action_container.cpp
===================================================================
--- pkg/trunk/deprecated/highlevel_controllers/src/action_container.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/deprecated/highlevel_controllers/src/action_container.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -36,7 +36,7 @@
#include <robot_actions/action_runner.h>
#include <robot_actions/action.h>
-#include <robot_actions/ShellCommandState.h>
+#include <pr2_robot_actions/ShellCommandState.h>
#include <std_msgs/String.h>
#include <cstdlib>
@@ -83,7 +83,7 @@
robot_actions::ActionRunner runner(10.0);
highlevel_controllers::ShellCommand shell_command;
- runner.connect<std_msgs::String, robot_actions::ShellCommandState, std_msgs::String>(shell_command);
+ runner.connect<std_msgs::String, pr2_robot_actions::ShellCommandState, std_msgs::String>(shell_command);
runner.run();
Modified: pkg/trunk/deprecated/highlevel_controllers/src/move_base.cpp
===================================================================
--- pkg/trunk/deprecated/highlevel_controllers/src/move_base.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/deprecated/highlevel_controllers/src/move_base.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -128,7 +128,7 @@
namespace highlevel_controllers {
MoveBase::MoveBase()
- : HighlevelController<robot_actions::MoveBaseState, robot_actions::Pose2D>("move_base", "feedback", "activate"),
+ : HighlevelController<pr2_robot_actions::MoveBaseState, pr2_robot_actions::Pose2D>("move_base", "feedback", "activate"),
tf_(*ros::Node::instance(), true, ros::Duration(10)), // cache for 10 sec, no extrapolation
controller_(NULL),
costMap_(NULL),
Modified: pkg/trunk/deprecated/highlevel_controllers/src/recharge_controller.cpp
===================================================================
--- pkg/trunk/deprecated/highlevel_controllers/src/recharge_controller.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/deprecated/highlevel_controllers/src/recharge_controller.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -66,7 +66,7 @@
#include <robot_actions/action.h>
#include <robot_actions/action_runner.h>
-#include <robot_actions/RechargeState.h>
+#include <pr2_robot_actions/RechargeState.h>
#include <robot_msgs/BatteryState.h>
#include <cstdlib>
@@ -268,7 +268,7 @@
highlevel_controllers::RechargeController recharge_controller("rechargeController");
- runner.connect<std_msgs::Float32, robot_actions::RechargeState, std_msgs::Float32>(recharge_controller);
+ runner.connect<std_msgs::Float32, pr2_robot_actions::RechargeState, std_msgs::Float32>(recharge_controller);
runner.run();
Modified: pkg/trunk/highlevel/doors/doors_core/include/doors_core/door_reactive_planner.h
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/include/doors_core/door_reactive_planner.h 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/include/doors_core/door_reactive_planner.h 2009-04-24 23:04:40 UTC (rev 14422)
@@ -37,7 +37,7 @@
#include <ros/node.h>
//messages
-#include <robot_actions/Pose2D.h>
+#include <pr2_robot_actions/Pose2D.h>
#include <robot_msgs/Vector3.h>
#include <robot_msgs/Point.h>
@@ -82,7 +82,7 @@
* @param start The position from which the robot is starting
* @param best_path The best path returned by the planner (note this could be a zero length path if no plan is found
*/
- bool makePlan(const robot_actions::Pose2D &start, std::vector<robot_actions::Pose2D> &best_path);
+ bool makePlan(const pr2_robot_actions::Pose2D &start, std::vector<pr2_robot_actions::Pose2D> &best_path);
/**
* @brief Set door information for the planner
@@ -96,7 +96,7 @@
* @param footprint_spec The footprint of the robot
* @param oriented_footprint The oriented footprint of the robot
*/
- bool computeOrientedFootprint(const robot_actions::Pose2D &position, const std::vector<robot_msgs::Point>& footprint_spec, std::vector<robot_msgs::Point>& oriented_footprint);
+ bool computeOrientedFootprint(const pr2_robot_actions::Pose2D &position, const std::vector<robot_msgs::Point>& footprint_spec, std::vector<robot_msgs::Point>& oriented_footprint);
std::vector<robot_msgs::Point> footprint_; /**< The footprint of the robot */
@@ -104,7 +104,7 @@
* @brief Get the goal position from the planner
* @return The goal position for the planner
*/
- bool getGoal(robot_actions::Pose2D &goal);
+ bool getGoal(pr2_robot_actions::Pose2D &goal);
private:
@@ -152,7 +152,7 @@
double centerline_angle_; /**< Angle that the normal to the door makes in the path_frame when the door is closed */
- robot_actions::Pose2D goal_; /**< Goal position on the other side of the doorway */
+ pr2_robot_actions::Pose2D goal_; /**< Goal position on the other side of the doorway */
bool door_information_set_ ; /**< Has door information been set before invoking the planner */
@@ -163,7 +163,7 @@
* @param p Position of the robot
* @param q Position of the robot
*/
- double distance(const robot_actions::Pose2D &p, const robot_actions::Pose2D &q);
+ double distance(const pr2_robot_actions::Pose2D &p, const pr2_robot_actions::Pose2D &q);
/**
* @brief Translational projected distance between two positions
@@ -171,7 +171,7 @@
* @param q Position of the robot
* @param angle angle of the vector to project onto of the robot
*/
- double projectedDistance(const robot_actions::Pose2D &p, const robot_actions::Pose2D &q, const double &angle);
+ double projectedDistance(const pr2_robot_actions::Pose2D &p, const pr2_robot_actions::Pose2D &q, const double &angle);
/**
* @brief Create a linear path between two positions
@@ -179,7 +179,7 @@
* @param fp Final position
* @param return_path The returned path
*/
- bool createLinearPath(const robot_actions::Pose2D &cp,const robot_actions::Pose2D &fp, std::vector<robot_actions::Pose2D> &return_path);
+ bool createLinearPath(const pr2_robot_actions::Pose2D &cp,const pr2_robot_actions::Pose2D &fp, std::vector<pr2_robot_actions::Pose2D> &return_path);
/**
* @brief Get the final position corresponding to motion along a straight line at angle (delta_angle) from the centerline_angle. The final position
@@ -189,7 +189,7 @@
* @param distance_to_centerline shortest distance from the current position to the centerline of the doorway
* @param end_position final position returned by this function
*/
- void getFinalPosition(const robot_actions::Pose2D ¤t_position, const double &delta_angle, const double &distance_to_centerline, robot_actions::Pose2D &end_position);
+ void getFinalPosition(const pr2_robot_actions::Pose2D ¤t_position, const double &delta_angle, const double &distance_to_centerline, pr2_robot_actions::Pose2D &end_position);
/**
* @brief The cost of a point in the cost map
@@ -206,7 +206,7 @@
* @param return_path The checked path to be returned
* @param costmap_frame_id The frame in which the map is specified
*/
- void checkPath(const std::vector<robot_actions::Pose2D> &path, const std::string &path_frame_id, std::vector<robot_actions::Pose2D> &return_path, std::string &costmap_frame_id);
+ void checkPath(const std::vector<pr2_robot_actions::Pose2D> &path, const std::string &path_frame_id, std::vector<pr2_robot_actions::Pose2D> &return_path, std::string &costmap_frame_id);
/**
* @brief Transform a path from one frame to another frame
@@ -215,7 +215,7 @@
* @param path_out The transformed path
* @param frame_in The frame in which the output path is specified
*/
- void transformPath(const std::vector<robot_actions::Pose2D> &path_in, const std::string &frame_in, std::vector<robot_actions::Pose2D> &path_out, const std::string &frame_out);
+ void transformPath(const std::vector<pr2_robot_actions::Pose2D> &path_in, const std::string &frame_in, std::vector<pr2_robot_actions::Pose2D> &path_out, const std::string &frame_out);
/**
* @brief Transform a 2D point from one frame to another
@@ -224,7 +224,7 @@
* @param path_out The transformed point
* @param frame_in The frame in which the output point is specified
*/
- void transform2DPose(const robot_actions::Pose2D &point_in, const std::string original_frame_id, robot_actions::Pose2D &point_out, const std::string &transform_frame_id);
+ void transform2DPose(const pr2_robot_actions::Pose2D &point_in, const std::string original_frame_id, pr2_robot_actions::Pose2D &point_out, const std::string &transform_frame_id);
};
}
Modified: pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h 2009-04-24 23:04:40 UTC (rev 14422)
@@ -41,8 +41,8 @@
#include <robot_actions/action.h>
#include <robot_actions/action_runner.h>
-#include <robot_actions/MoveBaseState.h>
-#include <robot_actions/Pose2D.h>
+#include <pr2_robot_actions/MoveBaseState.h>
+#include <pr2_robot_actions/Pose2D.h>
#include <robot_msgs/JointTraj.h>
#include <ros/node.h>
@@ -62,7 +62,7 @@
* @class MoveBaseDoorAction
* @brief A class adhering to the robot_actions::Action interface that moves the robot base to a goal location.
*/
- class MoveBaseDoorAction : public robot_actions::Action<robot_msgs::Door, robot_actions::Pose2D> {
+ class MoveBaseDoorAction : public robot_actions::Action<robot_msgs::Door, pr2_robot_actions::Pose2D> {
public:
/**
* @brief Constructor for the actions
@@ -83,7 +83,7 @@
* @param feedback Feedback that the action gives to a higher-level monitor, in this case, the position of the robot
* @return The result of the execution, ie: Success, Preempted, Aborted, etc.
*/
- virtual robot_actions::ResultStatus execute(const robot_msgs::Door& goal, robot_actions::Pose2D& feedback);
+ virtual robot_actions::ResultStatus execute(const robot_msgs::Door& goal, pr2_robot_actions::Pose2D& feedback);
private:
/**
@@ -102,7 +102,7 @@
/**
* @brief Publish a path for visualization purposes
*/
- void publishPath(const std::vector<robot_actions::Pose2D>& path, std::string topic, double r, double g, double b, double a);
+ void publishPath(const std::vector<pr2_robot_actions::Pose2D>& path, std::string topic, double r, double g, double b, double a);
/**
* @brief Make a new global plan (the goal is specified using the setDoor() function while start is specified using the
@@ -165,35 +165,35 @@
costmap_2d::Costmap2D planner_cost_map_;
door_reactive_planner::DoorReactivePlanner* planner_;
- std::vector<robot_actions::Pose2D> global_plan_;
+ std::vector<pr2_robot_actions::Pose2D> global_plan_;
std::vector<robot_msgs::Point> footprint_;
std::string global_frame_, control_frame_, robot_base_frame_;
bool valid_plan_;
boost::recursive_mutex lock_;
robot_msgs::Door door_;
- robot_actions::Pose2D goal_;
+ pr2_robot_actions::Pose2D goal_;
tf::Stamped<tf::Pose> global_pose_;
double xy_goal_tolerance_, yaw_goal_tolerance_, min_abs_theta_vel_;
double inscribed_radius_, circumscribed_radius_, inflation_radius_;
double controller_frequency_;
- std::vector<robot_actions::Pose2D> empty_plan_;
+ std::vector<pr2_robot_actions::Pose2D> empty_plan_;
std::string control_topic_name_;
/**
- * @brief Transform a tf::Stamped<tf::Pose> to robot_actions::Pose2D
+ * @brief Transform a tf::Stamped<tf::Pose> to pr2_robot_actions::Pose2D
* @param pose The pose object to be transformed
- * @return Transformed object of type robot_actions::Pose2D
+ * @return Transformed object of type pr2_robot_actions::Pose2D
*/
- robot_actions::Pose2D getPose2D(const tf::Stamped<tf::Pose> &pose);
+ pr2_robot_actions::Pose2D getPose2D(const tf::Stamped<tf::Pose> &pose);
/**
* @brief dispatch control commands
* @param plan_in The plan to be dispatched
*/
- void dispatchControl(const std::vector<robot_actions::Pose2D> &plan_in);
+ void dispatchControl(const std::vector<pr2_robot_actions::Pose2D> &plan_in);
};
};
#endif
Modified: pkg/trunk/highlevel/doors/doors_core/manifest.xml
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/manifest.xml 2009-04-24 23:04:40 UTC (rev 14422)
@@ -13,6 +13,7 @@
<depend package="robot_msgs" />
<depend package="robot_srvs" />
<depend package="robot_actions" />
+ <depend package="pr2_robot_actions" />
<depend package="kdl" />
<depend package="angles" />
<depend package="door_handle_detector" />
Modified: pkg/trunk/highlevel/doors/doors_core/src/action_runner.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/action_runner.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/src/action_runner.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -42,7 +42,7 @@
#include "doors_core/action_release_handle.h"
#include <robot_actions/action.h>
#include <robot_actions/action_runner.h>
-#include <robot_actions/DoorActionState.h>
+#include <pr2_robot_actions/DoorActionState.h>
using namespace door_handle_detector;
@@ -66,12 +66,12 @@
ReleaseHandleAction release(node);
robot_actions::ActionRunner runner(10.0);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(detect_door);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(detect_handle);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(grasp);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(unlatch);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(open);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(release);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(detect_door);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(detect_handle);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(grasp);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(unlatch);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(open);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(release);
runner.run();
node.spin();
Modified: pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -114,7 +114,7 @@
door_information_set_ = true;
}
-bool DoorReactivePlanner::getGoal(robot_actions::Pose2D &goal)
+bool DoorReactivePlanner::getGoal(pr2_robot_actions::Pose2D &goal)
{
if(!door_information_set_)
return false;
@@ -122,7 +122,7 @@
return true;
}
-bool DoorReactivePlanner::computeOrientedFootprint(const robot_actions::Pose2D &position, const std::vector<robot_msgs::Point>& footprint_spec, std::vector<robot_msgs::Point>& oriented_footprint)
+bool DoorReactivePlanner::computeOrientedFootprint(const pr2_robot_actions::Pose2D &position, const std::vector<robot_msgs::Point>& footprint_spec, std::vector<robot_msgs::Point>& oriented_footprint)
{
if(footprint_spec.size() < 3)//if we have no footprint... do nothing
{
@@ -141,20 +141,20 @@
return true;
}
-double DoorReactivePlanner::distance(const robot_actions::Pose2D &p, const robot_actions::Pose2D &q)
+double DoorReactivePlanner::distance(const pr2_robot_actions::Pose2D &p, const pr2_robot_actions::Pose2D &q)
{
return sqrt(pow(p.x-q.x,2)+pow(p.y-q.y,2));
}
-double DoorReactivePlanner::projectedDistance(const robot_actions::Pose2D &p, const robot_actions::Pose2D &q, const double &angle)
+double DoorReactivePlanner::projectedDistance(const pr2_robot_actions::Pose2D &p, const pr2_robot_actions::Pose2D &q, const double &angle)
{
return ((q.x-p.x)*cos(angle)+(q.y-p.y)*sin(angle));
}
-bool DoorReactivePlanner::createLinearPath(const robot_actions::Pose2D &cp,const robot_actions::Pose2D &fp, std::vector<robot_actions::Pose2D> &return_path)
+bool DoorReactivePlanner::createLinearPath(const pr2_robot_actions::Pose2D &cp,const pr2_robot_actions::Pose2D &fp, std::vector<pr2_robot_actions::Pose2D> &return_path)
{
ROS_DEBUG("Creating trajectory from: (%f,%f) to (%f,%f)",cp.x,cp.y,fp.x,fp.y);
- robot_actions::Pose2D temp;
+ pr2_robot_actions::Pose2D temp;
double dist_trans = distance(cp,fp);
double dist_rot = fabs(angles::normalize_angle(cp.th-fp.th));
@@ -182,7 +182,7 @@
return true;
}
-void DoorReactivePlanner::getFinalPosition(const robot_actions::Pose2D ¤t_position, const double &delta_angle, const double &distance_to_centerline, robot_actions::Pose2D &end_position)
+void DoorReactivePlanner::getFinalPosition(const pr2_robot_actions::Pose2D ¤t_position, const double &delta_angle, const double &distance_to_centerline, pr2_robot_actions::Pose2D &end_position)
{
double new_explore_distance;
double global_explore_angle;
@@ -215,17 +215,17 @@
}
-bool DoorReactivePlanner::makePlan(const robot_actions::Pose2D &start, std::vector<robot_actions::Pose2D> &best_path_control_frame)
+bool DoorReactivePlanner::makePlan(const pr2_robot_actions::Pose2D &start, std::vector<pr2_robot_actions::Pose2D> &best_path_control_frame)
{
if(!door_information_set_)
{
ROS_ERROR("Door information not set");
return false;
}
- std::vector<robot_actions::Pose2D> best_path_costmap_frame;
- robot_actions::Pose2D end_position;
- std::vector<robot_actions::Pose2D> checked_path;
- std::vector<robot_actions::Pose2D> linear_path;
+ std::vector<pr2_robot_actions::Pose2D> best_path_costmap_frame;
+ pr2_robot_actions::Pose2D end_position;
+ std::vector<pr2_robot_actions::Pose2D> checked_path;
+ std::vector<pr2_robot_actions::Pose2D> linear_path;
double min_distance_to_goal(FLT_MAX);
@@ -291,7 +291,7 @@
return true;
}
-void DoorReactivePlanner::checkPath(const std::vector<robot_actions::Pose2D> &path, const std::string &control_frame_id, std::vector<robot_actions::Pose2D> &return_path, std::string &costmap_frame_id)
+void DoorReactivePlanner::checkPath(const std::vector<pr2_robot_actions::Pose2D> &path, const std::string &control_frame_id, std::vector<pr2_robot_actions::Pose2D> &return_path, std::string &costmap_frame_id)
{
int index(0);
double theta;
@@ -305,7 +305,7 @@
{
index = i;
std::vector<robot_msgs::Point> oriented_footprint;
- robot_actions::Pose2D out_pose;
+ pr2_robot_actions::Pose2D out_pose;
transform2DPose(path[i],control_frame_id, out_pose, costmap_frame_id);
computeOrientedFootprint(out_pose, footprint_, oriented_footprint);
@@ -355,7 +355,7 @@
return true;
}
-void DoorReactivePlanner::transformPath(const std::vector<robot_actions::Pose2D> &path_in, const std::string &frame_in, std::vector<robot_actions::Pose2D> &path_out, const std::string &frame_out)
+void DoorReactivePlanner::transformPath(const std::vector<pr2_robot_actions::Pose2D> &path_in, const std::string &frame_in, std::vector<pr2_robot_actions::Pose2D> &path_out, const std::string &frame_out)
{
path_out.resize((int) path_in.size());
for(int i=0; i < (int) path_out.size(); i++)
@@ -364,7 +364,7 @@
}
}
-void DoorReactivePlanner::transform2DPose(const robot_actions::Pose2D &point_in, const std::string original_frame_id, robot_actions::Pose2D &point_out, const std::string &transform_frame_id)
+void DoorReactivePlanner::transform2DPose(const pr2_robot_actions::Pose2D &point_in, const std::string original_frame_id, pr2_robot_actions::Pose2D &point_out, const std::string &transform_frame_id)
{
btQuaternion qt;
tf::Stamped<tf::Pose> pose;
Modified: pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -36,7 +36,7 @@
*********************************************************************/
#include <doors_core/move_base_door_action.h>
#include <doors_core/door_reactive_planner.h>
-#include <robot_actions/MoveBaseDoorState.h>
+#include <pr2_robot_actions/MoveBaseDoorState.h>
using namespace base_local_planner;
@@ -46,7 +46,7 @@
namespace nav
{
MoveBaseDoorAction::MoveBaseDoorAction(ros::Node& ros_node, tf::TransformListener& tf) :
- Action<robot_msgs::Door, robot_actions::Pose2D>("move_base_door"), ros_node_(ros_node), tf_(tf),
+ Action<robot_msgs::Door, pr2_robot_actions::Pose2D>("move_base_door"), ros_node_(ros_node), tf_(tf),
run_planner_(true), planner_cost_map_ros_(NULL),
planner_(NULL), valid_plan_(false)
{
@@ -103,9 +103,9 @@
}
- robot_actions::Pose2D MoveBaseDoorAction::getPose2D(const tf::Stamped<tf::Pose> &pose)
+ pr2_robot_actions::Pose2D MoveBaseDoorAction::getPose2D(const tf::Stamped<tf::Pose> &pose)
{
- robot_actions::Pose2D tmp_pose;
+ pr2_robot_actions::Pose2D tmp_pose;
double useless_pitch, useless_roll, yaw;
pose.getBasis().getEulerZYX(yaw, useless_pitch, useless_roll);
tmp_pose.x = pose.getOrigin().x();
@@ -121,7 +121,7 @@
//get the oriented footprint of the robot
std::vector<robot_msgs::Point> oriented_footprint;
- robot_actions::Pose2D tmp_pose = getPose2D(global_pose_);
+ pr2_robot_actions::Pose2D tmp_pose = getPose2D(global_pose_);
planner_->computeOrientedFootprint(tmp_pose, planner_->footprint_, oriented_footprint);
//set the associated costs in the cost map to be free
@@ -146,7 +146,7 @@
//make sure we clear the robot's footprint from the cost map
//clearRobotFootprint(planner_cost_map_);
- std::vector<robot_actions::Pose2D> global_plan;
+ std::vector<pr2_robot_actions::Pose2D> global_plan;
bool valid_plan = planner_->makePlan(getPose2D(global_pose_), global_plan);//makePlan(current_position, return_path);
lock_.lock();//copy over the new global plan
@@ -209,9 +209,9 @@
void MoveBaseDoorAction::prunePlan()
{
lock_.lock();
- std::vector<robot_actions::Pose2D>::iterator it = global_plan_.begin();
+ std::vector<pr2_robot_actions::Pose2D>::iterator it = global_plan_.begin();
while(it != global_plan_.end()){
- const robot_actions::Pose2D& w = *it;
+ const pr2_robot_actions::Pose2D& w = *it;
// Fixed error bound of 2 meters for now. Can reduce to a portion of the map size or based on the resolution
double x_diff = global_pose_.getOrigin().x() - w.x;
double y_diff = global_pose_.getOrigin().y() - w.y;
@@ -225,7 +225,7 @@
lock_.unlock();
}
- robot_actions::ResultStatus MoveBaseDoorAction::execute(const robot_msgs::Door& door, robot_actions::Pose2D& feedback)
+ robot_actions::ResultStatus MoveBaseDoorAction::execute(const robot_msgs::Door& door, pr2_robot_actions::Pose2D& feedback)
{
door_ = door;
planner_->setDoor(door);//set the goal into the planner
@@ -297,7 +297,7 @@
return robot_actions::PREEMPTED;
}
- void MoveBaseDoorAction::dispatchControl(const std::vector<robot_actions::Pose2D> &plan_in)
+ void MoveBaseDoorAction::dispatchControl(const std::vector<pr2_robot_actions::Pose2D> &plan_in)
{
robot_msgs::JointTraj plan_out;
if((int)plan_in.size() <= 0)
@@ -372,7 +372,7 @@
ros_node_.publish("robot_footprint", footprint_msg);
}
- void MoveBaseDoorAction::publishPath(const std::vector<robot_actions::Pose2D>& path, std::string topic, double r, double g, double b, double a){
+ void MoveBaseDoorAction::publishPath(const std::vector<pr2_robot_actions::Pose2D>& path, std::string topic, double r, double g, double b, double a){
// Extract the plan in world co-ordinates
robot_msgs::Polyline gui_path_msg;
gui_path_msg.header.frame_id = global_frame_;
@@ -414,11 +414,11 @@
ros::Time my_time = ros::Time::now();
door.header.stamp = my_time;
- robot_actions::Pose2D feedback;
+ pr2_robot_actions::Pose2D feedback;
move_base_door.execute(door,feedback);
*/
robot_actions::ActionRunner runner(20.0);
- runner.connect<robot_msgs::Door, MoveBaseDoorState, robot_actions::Pose2D>(move_base_door);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::MoveBaseDoorState, pr2_robot_actions::Pose2D>(move_base_door);
runner.run();
ros_node.spin();
Modified: pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/test/test_executive.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -42,12 +42,12 @@
#include <robot_msgs/Door.h>
#include <ros/node.h>
#include <robot_actions/action_client.h>
-#include <robot_actions/Pose2D.h>
-#include <robot_actions/DoorActionState.h>
+#include <pr2_robot_actions/Pose2D.h>
+#include <pr2_robot_actions/DoorActionState.h>
#include <robot_actions/NoArgumentsActionState.h>
-#include <robot_actions/SwitchControllersState.h>
-#include <robot_actions/MoveBaseStateNew.h>
-#include <robot_actions/MoveBaseDoorState.h>
+#include <pr2_robot_actions/SwitchControllersState.h>
+#include <pr2_robot_actions/MoveBaseStateNew.h>
+#include <pr2_robot_actions/MoveBaseDoorState.h>
#include "doors_core/executive_functions.h"
@@ -75,7 +75,7 @@
door.hinge = -1;
door.header.frame_id = "base_footprint";
- robot_actions::SwitchControllers switchlist;
+ pr2_robot_actions::SwitchControllers switchlist;
std_msgs::Empty empty;
Duration timeout_short = Duration().fromSec(2.0);
@@ -83,15 +83,15 @@
Duration timeout_long = Duration().fromSec(20.0);
robot_actions::ActionClient<std_msgs::Empty, robot_actions::NoArgumentsActionState, std_msgs::Empty> tuck_arm("doors_tuck_arms");
- robot_actions::ActionClient<robot_actions::SwitchControllers, robot_actions::SwitchControllersState, std_msgs::Empty> switch_controllers("switch_controllers");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> detect_door("detect_door");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> detect_handle("detect_handle");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> grasp_handle("grasp_handle");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> unlatch_handle("unlatch_handle");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> open_door("open_door");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> release_handle("release_handle");
- robot_actions::ActionClient<robot_msgs::Door, robot_actions::MoveBaseDoorState, robot_actions::Pose2D> move_base_door("move_base_door");
- robot_actions::ActionClient<robot_msgs::PoseStamped, robot_actions::MoveBaseStateNew, robot_msgs::PoseStamped> move_base_local("move_base_local");
+ robot_actions::ActionClient<pr2_robot_actions::SwitchControllers, pr2_robot_actions::SwitchControllersState, std_msgs::Empty> switch_controllers("switch_controllers");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> detect_door("detect_door");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> detect_handle("detect_handle");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> grasp_handle("grasp_handle");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> unlatch_handle("unlatch_handle");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> open_door("open_door");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> release_handle("release_handle");
+ robot_actions::ActionClient<robot_msgs::Door, pr2_robot_actions::MoveBaseDoorState, pr2_robot_actions::Pose2D> move_base_door("move_base_door");
+ robot_actions::ActionClient<robot_msgs::PoseStamped, pr2_robot_actions::MoveBaseStateNew, robot_msgs::PoseStamped> move_base_local("move_base_local");
timeout_medium.sleep();
robot_msgs::Door tmp_door;
@@ -146,11 +146,11 @@
switchlist.start_controllers.clear(); switchlist.stop_controllers.clear();
if (switch_controllers.execute(switchlist, empty, timeout_short) != robot_actions::SUCCESS) return -1;
boost::thread* thread = new boost::thread(boost::bind(&robot_actions::ActionClient<robot_msgs::Door,
- robot_actions::DoorActionState, robot_msgs::Door>::execute,
+ pr2_robot_actions::DoorActionState, robot_msgs::Door>::execute,
&open_door, door, tmp_door, timeout_long));
// move throught door
- robot_actions::Pose2D pose2d;
+ pr2_robot_actions::Pose2D pose2d;
switchlist.start_controllers.clear(); switchlist.stop_controllers.clear();
if (switch_controllers.execute(switchlist, empty, timeout_short) != robot_actions::SUCCESS) {open_door.preempt(); return -1;};
if (move_base_door.execute(door, pose2d, timeout_long) != robot_actions::SUCCESS) {open_door.preempt(); return -1;};
Modified: pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_detector.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_detector.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_detector.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -39,7 +39,7 @@
#include "doors_core/action_detect_door.h"
#include "doors_core/action_detect_handle.h"
-#include <robot_actions/DoorActionState.h>
+#include <pr2_robot_actions/DoorActionState.h>
#include <robot_msgs/Door.h>
#include <ros/node.h>
#include <robot_actions/action_runner.h>
@@ -72,8 +72,8 @@
door_handle_detector::DetectDoorAction door_detector(node);
door_handle_detector::DetectHandleAction handle_detector(node);
robot_actions::ActionRunner runner(10.0);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(door_detector);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(handle_detector);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(door_detector);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(handle_detector);
runner.run();
robot_msgs::Door feedback;
Modified: pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_opener.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_opener.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/test/trigger_doors_opener.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -38,7 +38,7 @@
/* Author: Wim Meeussen */
#include "doors_core/action_open_door.h"
-#include <robot_actions/DoorActionState.h>
+#include <pr2_robot_actions/DoorActionState.h>
#include <robot_msgs/Door.h>
#include <ros/node.h>
#include <robot_actions/action_runner.h>
@@ -70,7 +70,7 @@
door_handle_detector::OpenDoorAction door_opener(node);
robot_actions::ActionRunner runner(10.0);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(door_opener);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(door_opener);
runner.run();
robot_msgs::Door feedback;
Modified: pkg/trunk/highlevel/doors/doors_core/test/trigger_handle_release.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/test/trigger_handle_release.cpp 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/doors/doors_core/test/trigger_handle_release.cpp 2009-04-24 23:04:40 UTC (rev 14422)
@@ -36,7 +36,7 @@
*********************************************************************/
#include "doors_core/action_release_handle.h"
-#include <robot_actions/DoorActionState.h>
+#include <pr2_robot_actions/DoorActionState.h>
#include <robot_msgs/Door.h>
#include <ros/node.h>
#include <robot_actions/action_runner.h>
@@ -68,7 +68,7 @@
door_handle_detector::ReleaseHandleAction release_handle(node);
robot_actions::ActionRunner runner(10.0);
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(release_handle);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(release_handle);
runner.run();
robot_msgs::Door feedback;
Modified: pkg/trunk/highlevel/executive_python/manifest.xml
===================================================================
--- pkg/trunk/highlevel/executive_python/manifest.xml 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_python/manifest.xml 2009-04-24 23:04:40 UTC (rev 14422)
@@ -7,5 +7,5 @@
<depend package="nav" />
<depend package="std_msgs" />
<depend package="robot_msgs" />
- <depend package="robot_actions" />
+ <depend package="pr2_robot_actions" />
</package>
Modified: pkg/trunk/highlevel/executive_python/src/navigation_adapter.py
===================================================================
--- pkg/trunk/highlevel/executive_python/src/navigation_adapter.py 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_python/src/navigation_adapter.py 2009-04-24 23:04:40 UTC (rev 14422)
@@ -38,7 +38,7 @@
roslib.load_manifest('executive_python')
import rospy
import random
-from robot_actions.msg import MoveBaseStateNew
+from pr2_robot_actions.msg import MoveBaseStateNew
from robot_msgs.msg import PoseStamped
class NavigationAdapter:
Modified: pkg/trunk/highlevel/executive_python/src/recharge_adapter.py
===================================================================
--- pkg/trunk/highlevel/executive_python/src/recharge_adapter.py 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_python/src/recharge_adapter.py 2009-04-24 23:04:40 UTC (rev 14422)
@@ -37,7 +37,7 @@
import roslib
roslib.load_manifest('executive_python')
import rospy
-from robot_actions.msg import RechargeState
+from pr2_robot_actions.msg import RechargeState
from std_msgs.msg import Float32
class RechargeAdapter:
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapter_utilities.h
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapter_utilities.h 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapter_utilities.h 2009-04-24 23:04:40 UTC (rev 14422)
@@ -12,7 +12,7 @@
#include <std_msgs/String.h>
#include <robot_msgs/Door.h>
#include <robot_msgs/PlugStow.h>
-#include <robot_actions/ServoToOutlet.h>
+//#include <pr2_robot_actions/ServoToOutlet.h> //Not used?
#include <robot_msgs/PointStamped.h>
#include <robot_msgs/PoseStamped.h>
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapters.h
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapters.h 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/include/executive_trex_pr2/adapters.h 2009-04-24 23:04:40 UTC (rev 14422)
@@ -49,16 +49,16 @@
#include <robot_actions/action_runner.h>
#include <robot_actions/action.h>
#include <robot_actions/NoArgumentsActionState.h>
-#include <robot_actions/DoorActionState.h>
-#include <robot_actions/CheckPathState.h>
-#include <robot_actions/NotifyDoorBlockedState.h>
-#include <robot_actions/ShellCommandState.h>
-#include <robot_actions/MoveBaseStateNew.h>
-#include <robot_actions/Pose2D.h>
-#include <robot_actions/RechargeState.h>
-#include <robot_actions/DetectPlugOnBaseState.h>
-#include <robot_actions/MoveAndGraspPlugState.h>
-#include <robot_actions/StowPlugState.h>
-#include <robot_actions/SwitchControllers.h>
-#include <robot_actions/SwitchControllersState.h>
-#include <robot_actions/DetectOutletState.h>
+#include <pr2_robot_actions/DoorActionState.h>
+#include <pr2_robot_actions/CheckPathState.h>
+#include <pr2_robot_actions/NotifyDoorBlockedState.h>
+#include <pr2_robot_actions/ShellCommandState.h>
+#include <pr2_robot_actions/MoveBaseStateNew.h>
+#include <pr2_robot_actions/Pose2D.h>
+#include <pr2_robot_actions/RechargeState.h>
+#include <pr2_robot_actions/DetectPlugOnBaseState.h>
+#include <pr2_robot_actions/MoveAndGraspPlugState.h>
+#include <pr2_robot_actions/StowPlugState.h>
+#include <pr2_robot_actions/SwitchControllers.h>
+#include <pr2_robot_actions/SwitchControllersState.h>
+#include <pr2_robot_actions/DetectOutletState.h>
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/manifest.xml 2009-04-24 23:04:40 UTC (rev 14422)
@@ -9,6 +9,7 @@
<depend package="topological_map" />
<depend package="doors_core" />
<depend package="robot_actions" />
+ <depend package="pr2_robot_actions" />
<depend package="pr2_msgs" />
<depend package="std_msgs" />
<depend package="robot_msgs" />
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/adapters.cc
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/adapters.cc 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/adapters.cc 2009-04-24 23:04:40 UTC (rev 14422)
@@ -48,11 +48,11 @@
/***********************************************************************
* @brief Door actions operate with a door message for goal and feedback
***********************************************************************/
- class DoorActionAdapter: public ROSActionAdapter<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door> {
+ class DoorActionAdapter: public ROSActionAdapter<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door> {
public:
DoorActionAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(agentName, configData){
+ : ROSActionAdapter<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(agentName, configData){
}
virtual void fillActiveObservationParameters(const robot_msgs::Door& msg, ObservationByValue* obs){
@@ -74,11 +74,11 @@
/***********************************************************************
* @brief MoveBase actions with a pose message for goal and feedback
**********************************************************************/
- class MoveBaseAdapter: public ROSActionAdapter<robot_msgs::PoseStamped, robot_actions::MoveBaseStateNew, robot_msgs::PoseStamped> {
+ class MoveBaseAdapter: public ROSActionAdapter<robot_msgs::PoseStamped, pr2_robot_actions::MoveBaseStateNew, robot_msgs::PoseStamped> {
public:
MoveBaseAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_msgs::PoseStamped, robot_actions::MoveBaseStateNew, robot_msgs::PoseStamped>(agentName, configData){
+ : ROSActionAdapter<robot_msgs::PoseStamped, pr2_robot_actions::MoveBaseStateNew, robot_msgs::PoseStamped>(agentName, configData){
}
virtual void fillDispatchParameters(robot_msgs::PoseStamped& msg, const TokenId& goalToken){
@@ -101,11 +101,11 @@
/***********************************************************************
* @brief CheckPath
**********************************************************************/
- class CheckPathAdapter: public ROSActionAdapter<robot_msgs::PoseStamped, robot_actions::CheckPathState, int8_t> {
+ class CheckPathAdapter: public ROSActionAdapter<robot_msgs::PoseStamped, pr2_robot_actions::CheckPathState, int8_t> {
public:
CheckPathAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_msgs::PoseStamped, robot_actions::CheckPathState, int8_t>(agentName, configData){
+ : ROSActionAdapter<robot_msgs::PoseStamped, pr2_robot_actions::CheckPathState, int8_t>(agentName, configData){
}
virtual void fillDispatchParameters(robot_msgs::PoseStamped& msg, const TokenId& goalToken){
@@ -143,11 +143,11 @@
/***********************************************************************
* @@brief Recharge action
**********************************************************************/
- class RechargeAdapter: public ROSActionAdapter<std_msgs::Float32, robot_actions::RechargeState, std_msgs::Float32> {
+ class RechargeAdapter: public ROSActionAdapter<std_msgs::Float32, pr2_robot_actions::RechargeState, std_msgs::Float32> {
public:
RechargeAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<std_msgs::Float32, robot_actions::RechargeState, std_msgs::Float32>(agentName, configData){}
+ : ROSActionAdapter<std_msgs::Float32, pr2_robot_actions::RechargeState, std_msgs::Float32>(agentName, configData){}
virtual void fillActiveObservationParameters(const std_msgs::Float32& msg, ObservationByValue* obs){
AdapterUtilities::read<float>("recharge_level", *obs, msg.data);
@@ -170,11 +170,11 @@
* @brief ShellCommand action will take system commands in strings and
* ship them for execution.
**********************************************************************/
- class ShellCommandAdapter: public ROSActionAdapter<std_msgs::String, robot_actions::ShellCommandState, std_msgs::String> {
+ class ShellCommandAdapter: public ROSActionAdapter<std_msgs::String, pr2_robot_actions::ShellCommandState, std_msgs::String> {
public:
ShellCommandAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<std_msgs::String, robot_actions::ShellCommandState, std_msgs::String>(agentName, configData){
+ : ROSActionAdapter<std_msgs::String, pr2_robot_actions::ShellCommandState, std_msgs::String>(agentName, configData){
}
virtual void fillActiveObservationParameters(const std_msgs::String& msg, ObservationByValue* obs){
@@ -218,11 +218,11 @@
/***********************************************************************
* @brief DetectPlugOnBase
**********************************************************************/
- class DetectPlugOnBaseAdapter: public ROSActionAdapter<std_msgs::Empty, robot_actions::DetectPlugOnBaseState, robot_msgs::PlugStow> {
+ class DetectPlugOnBaseAdapter: public ROSActionAdapter<std_msgs::Empty, pr2_robot_actions::DetectPlugOnBaseState, robot_msgs::PlugStow> {
public:
DetectPlugOnBaseAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<std_msgs::Empty, robot_actions::DetectPlugOnBaseState, robot_msgs::PlugStow>(agentName, configData){
+ : ROSActionAdapter<std_msgs::Empty, pr2_robot_actions::DetectPlugOnBaseState, robot_msgs::PlugStow>(agentName, configData){
}
virtual void fillInactiveObservationParameters(const robot_msgs::PlugStow& msg, ObservationByValue* obs){
@@ -236,11 +236,11 @@
/***********************************************************************
* @brief MoveAndGraspPlug
**********************************************************************/
- class MoveAndGraspPlugAdapter: public ROSActionAdapter<robot_msgs::PlugStow, robot_actions::MoveAndGraspPlugState, std_msgs::Empty> {
+ class MoveAndGraspPlugAdapter: public ROSActionAdapter<robot_msgs::PlugStow, pr2_robot_actions::MoveAndGraspPlugState, std_msgs::Empty> {
public:
MoveAndGraspPlugAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_msgs::PlugStow, robot_actions::MoveAndGraspPlugState, std_msgs::Empty>(agentName, configData){
+ : ROSActionAdapter<robot_msgs::PlugStow, pr2_robot_actions::MoveAndGraspPlugState, std_msgs::Empty>(agentName, configData){
}
virtual void fillActiveObservationParameters(const robot_msgs::PlugStow& msg, ObservationByValue* obs){
@@ -259,11 +259,11 @@
/***********************************************************************
* @brief StowPlug
**********************************************************************/
- class StowPlugAdapter: public ROSActionAdapter<robot_msgs::PlugStow, robot_actions::StowPlugState, std_msgs::Empty> {
+ class StowPlugAdapter: public ROSActionAdapter<robot_msgs::PlugStow, pr2_robot_actions::StowPlugState, std_msgs::Empty> {
public:
StowPlugAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_msgs::PlugStow, robot_actions::StowPlugState, std_msgs::Empty>(agentName, configData){
+ : ROSActionAdapter<robot_msgs::PlugStow, pr2_robot_actions::StowPlugState, std_msgs::Empty>(agentName, configData){
}
virtual void fillDispatchParameters(robot_msgs::PlugStow& msg, const TokenId& goalToken){
@@ -282,14 +282,14 @@
/***********************************************************************
* @brief SwtichControllers action
**********************************************************************/
- class SwitchControllersAdapter: public ROSActionAdapter<robot_actions::SwitchControllers, robot_actions::SwitchControllersState, std_msgs::Empty> {
+ class SwitchControllersAdapter: public ROSActionAdapter<pr2_robot_actions::SwitchControllers, pr2_robot_actions::SwitchControllersState, std_msgs::Empty> {
public:
SwitchControllersAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_actions::SwitchControllers, robot_actions::SwitchControllersState, std_msgs::Empty>(agentName, configData){
+ : ROSActionAdapter<pr2_robot_actions::SwitchControllers, pr2_robot_actions::SwitchControllersState, std_msgs::Empty>(agentName, configData){
}
- void fillDispatchParameters(robot_actions::SwitchControllers& msg, const TokenId& goalToken){
+ void fillDispatchParameters(pr2_robot_actions::SwitchControllers& msg, const TokenId& goalToken){
// The token will have a set of merged tokens on it. These merged tokens all are derived from a master of type
// 'MechanismController' which will be in a state of up or down. If it is up, we will append to the stop list, and if down, we
// will append to the start list
@@ -309,7 +309,7 @@
* The Master Token is an instance of a MechanismController. It has a paramater indicating if it is up or down. The timeline name
* should correspond to the actual controller name.
*/
- void handleMasterToken(const TokenId& master_token, robot_actions::SwitchControllers& msg){
+ void handleMasterToken(const TokenId& master_token, pr2_robot_actions::SwitchControllers& msg){
if(master_token.isId() && master_token->getPlanDatabase()->getSchema()->isA(master_token->getPredicateName(), "MechanismController.Holds")){
ConstrainedVariableId param = master_token->getVariable("is_up");
checkError(param.isValid(), "Trying to dispatch controller switch but could find no variable named 'is_up' in token " << master_token->toString() <<
@@ -338,11 +338,11 @@
/***********************************************************************
* @brief DetectOutletAdapter
**********************************************************************/
- class DetectOutletAdapter: public ROSActionAdapter<robot_msgs::PointStamped, robot_actions::DetectOutletState, robot_msgs::PoseStamped> {
+ class DetectOutletAdapter: public ROSActionAdapter<robot_msgs::PointStamped, pr2_robot_actions::DetectOutletState, robot_msgs::PoseStamped> {
public:
DetectOutletAdapter(const LabelStr& agentName, const TiXmlElement& configData)
- : ROSActionAdapter<robot_msgs::PointStamped, robot_actions::DetectOutletState, robot_msgs::PoseStamped>(agentName, configData){
+ : ROSActionAdapter<robot_msgs::PointStamped, pr2_robot_actions::DetectOutletState, robot_msgs::PoseStamped>(agentName, configData){
}
virtual void fillDispatchParameters(robot_msgs::PointStamped& msg, const TokenId& goalToken){
Modified: pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/stub_ros_container.cc
===================================================================
--- pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/stub_ros_container.cc 2009-04-24 22:37:34 UTC (rev 14421)
+++ pkg/trunk/highlevel/executive_trex/executive_trex_pr2/src/stub_ros_container.cc 2009-04-24 23:04:40 UTC (rev 14422)
@@ -156,56 +156,56 @@
executive_trex_pr2::StubAction<robot_msgs::PoseStamped, int8_t> check_path("check_path");
if (getComponentParam("/trex/enable_check_path"))
- runner.connect<robot_msgs::PoseStamped, robot_actions::CheckPathState, int8_t>(check_path);
+ runner.connect<robot_msgs::PoseStamped, pr2_robot_actions::CheckPathState, int8_t>(check_path);
// Detect Door
executive_trex_pr2::SimpleStubAction<robot_msgs::Door> detect_door("detect_door");
if (getComponentParam("/trex/enable_detect_door"))
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(detect_door);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(detect_door);
// Detect Handle
executive_trex_pr2::SimpleStubAction<robot_msgs::Door> detect_handle("detect_handle");
if (getComponentParam("/trex/enable_detect_handle"))
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(detect_handle);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(detect_handle);
// Grasp Handle
executive_trex_pr2::SimpleStubAction<robot_msgs::Door> grasp_handle("grasp_handle");
if (getComponentParam("/trex/enable_grasp_handle"))
- runner.connect<robot_msgs::Door, robot_actions::DoorActionState, robot_msgs::Door>(grasp_handle);
+ runner.connect<robot_msgs::Door, pr2_robot_actions::DoorActionState, robot_msgs::Door>(grasp_handle);
// Unlatch Handle
executive_trex_pr2::SimpleStubAction<robot_msgs::Door> unlatch_handle("unlatch_handle");
if (getCompo...
[truncated message content] |