|
From: <tpr...@us...> - 2009-02-21 02:22:27
|
Revision: 11505
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=11505&view=rev
Author: tpratkanis
Date: 2009-02-21 01:50:27 +0000 (Sat, 21 Feb 2009)
Log Message:
-----------
Remove done and valid booleans from highlevel controller state messages.
Modified Paths:
--------------
pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh
pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg
pkg/trunk/highlevel/highlevel_controllers/src/move_arm2.cpp
pkg/trunk/pr2_msgs/msg/MoveArmState.msg
pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg
pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg
Modified: pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh 2009-02-21 01:42:39 UTC (rev 11504)
+++ pkg/trunk/highlevel/highlevel_controllers/include/highlevel_controllers/highlevel_controller.hh 2009-02-21 01:50:27 UTC (rev 11505)
@@ -70,7 +70,8 @@
*/
HighlevelController(const std::string& nodeName, const std::string& _stateTopic, const std::string& _goalTopic):
initialized(false), terminated(false), stateTopic(_stateTopic),
- goalTopic(_goalTopic), controllerCycleTime_(0.1), plannerCycleTime_(0.0), plannerThread_(NULL), timeout(0, 0) {
+ goalTopic(_goalTopic), controllerCycleTime_(0.1), plannerCycleTime_(0.0), plannerThread_(NULL),
+ timeout(0, 0), done_(false), valid_(false) {
// Obtain the control frequency for this node
double controller_frequency(10);
@@ -204,7 +205,7 @@
* @brief Access for valid status of the controller
*/
bool isValid() {
- return this->stateMsg.valid;
+ return valid_;
}
/**
* @brief Access aborted state of the planner.
@@ -229,7 +230,7 @@
this->state = ACTIVE;
this->stateMsg.status = this->stateMsg.ACTIVE;
- this->stateMsg.done = 0;
+ done_ = 0;
handleActivation();
}
@@ -244,7 +245,7 @@
if (this->stateMsg.status == this->stateMsg.ACTIVE) {
this->stateMsg.status = this->stateMsg.INACTIVE;
}
- this->stateMsg.valid = 0;
+ valid_ = 0;
handleDeactivation();
}
@@ -352,6 +353,28 @@
G goalMsg; /*!< Message populated by callback */
S stateMsg; /*!< Message published. Will be populated in the control loop */
+ /**
+ * @brief Setter for state msg done flag
+ */
+ void setDone(bool isDone){
+ done_ = isDone;
+ }
+
+ /**
+ * @brief Get the done flag
+ */
+ bool getDone() {
+ return done_;
+ }
+
+ /**
+ * @brief Setter for state msg valid flag
+ */
+ void setValid(bool isValid){
+ valid_ = isValid;
+ }
+
+
private:
void goalCallback(){
@@ -452,20 +475,7 @@
unlock();
}
- /**
- * @brief Setter for state msg done flag
- */
- void setDone(bool isDone){
- this->stateMsg.done = isDone;
- }
- /**
- * @brief Setter for state msg valid flag
- */
- void setValid(bool isValid){
- this->stateMsg.valid = isValid;
- }
-
bool initialized; /*!< Marks if the node has been initialized, and is ready for use. */
bool terminated; /*!< Marks if the node has been terminated. */
const std::string stateTopic; /*!< The topic on which state updates are published */
@@ -477,6 +487,8 @@
boost::thread* plannerThread_; /*!< Thread running the planner loop */
highlevel_controllers::Ping shutdownMsg_; /*!< For receiving shutdown from executive */
ros::Duration timeout; /*< The time limit for planning failure. */
+ bool done_; /*< True if the action is done */
+ bool valid_; /*< True if it is valid */
};
#endif
Modified: pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg 2009-02-21 01:42:39 UTC (rev 11504)
+++ pkg/trunk/highlevel/highlevel_controllers/msg/RechargeState.msg 2009-02-21 01:50:27 UTC (rev 11505)
@@ -15,13 +15,6 @@
#Comment for debug
string comment
-
-# Did the controller find a valid path?
-byte valid
-
-# Have we arrived at the goal?
-byte done
-
# Actual recharge level
float32 recharge_level
Modified: pkg/trunk/highlevel/highlevel_controllers/src/move_arm2.cpp
===================================================================
--- pkg/trunk/highlevel/highlevel_controllers/src/move_arm2.cpp 2009-02-21 01:42:39 UTC (rev 11504)
+++ pkg/trunk/highlevel/highlevel_controllers/src/move_arm2.cpp 2009-02-21 01:50:27 UTC (rev 11505)
@@ -201,7 +201,6 @@
{
lock();
stateMsg.goal = goalMsg.configuration;
- stateMsg.valid = false;
unlock();
}
@@ -303,7 +302,7 @@
if (!ret)
ROS_ERROR("Service call on plan_kinematic_path_state failed");
else
- stateMsg.done = res.value.done;
+ setDone(res.value.done);
ROS_INFO("Plan created.");
@@ -334,19 +333,19 @@
bool MoveArm::goalReached()
{
- return stateMsg.done;
+ return getDone();
}
bool MoveArm::dispatchCommands()
{
puts("in dispatchCommands");
lock();
- if (stateMsg.done || !isValid())
+ if (getDone() || !isValid())
stopArm();
else if (trajectory_changed_)
sendArmCommand(current_trajectory_, kinematic_model_);
unlock();
- return stateMsg.valid; //Do not change.
+ return isValid(); //Do not change.
}
void MoveArm::printKinematicPath(robot_msgs::KinematicPath &path)
Modified: pkg/trunk/pr2_msgs/msg/MoveArmState.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/MoveArmState.msg 2009-02-21 01:42:39 UTC (rev 11504)
+++ pkg/trunk/pr2_msgs/msg/MoveArmState.msg 2009-02-21 01:50:27 UTC (rev 11505)
@@ -16,10 +16,6 @@
#Comment for debug
string comment
-#Did we reach the goal?
-byte done
-#Did the planner/controller find a valid way to achieve the goal
-byte valid
#Current arm configuration
robot_msgs/JointState[] configuration
#Goal arm configuration
Modified: pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg
===================================================================
--- pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg 2009-02-21 01:42:39 UTC (rev 11504)
+++ pkg/trunk/pr2_msgs/msg/MoveEndEffectorState.msg 2009-02-21 01:50:27 UTC (rev 11505)
@@ -15,10 +15,6 @@
#Comment for debug
string comment
-#Did the planner/controller find a valid way to achieve the goal
-byte valid
-#Did we actually successfully arrive at the goal?
-byte done
#Current arm configuration
robot_msgs/JointState[] configuration
#Goal arm configuration
Modified: pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg 2009-02-21 01:42:39 UTC (rev 11504)
+++ pkg/trunk/prcore/robot_msgs/msg/Planner2DState.msg 2009-02-21 01:50:27 UTC (rev 11505)
@@ -16,10 +16,6 @@
#Comment for debug
string comment
-# Did the planner find a valid path?
-byte valid
-# Have we arrived at the goal?
-byte done
# Current location (m,m,rad)
deprecated_msgs/Pose2DFloat32 pos
# Goal location (m,m,rad)
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|