|
From: <tpr...@us...> - 2009-06-18 01:23:05
|
Revision: 17266
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17266&view=rev
Author: tpratkanis
Date: 2009-06-18 00:40:41 +0000 (Thu, 18 Jun 2009)
Log Message:
-----------
Fix some things in robot actions.
Modified Paths:
--------------
pkg/trunk/common/robot_actions/include/robot_actions/action.h
pkg/trunk/common/robot_actions/msg/ActionStatus.msg
pkg/trunk/highlevel/robot_actions_tools/list_action_state.py
pkg/trunk/highlevel/test_robot_actions/test/utest.cc
Modified: pkg/trunk/common/robot_actions/include/robot_actions/action.h
===================================================================
--- pkg/trunk/common/robot_actions/include/robot_actions/action.h 2009-06-18 00:40:41 UTC (rev 17265)
+++ pkg/trunk/common/robot_actions/include/robot_actions/action.h 2009-06-18 00:40:41 UTC (rev 17266)
@@ -51,6 +51,7 @@
#include <boost/thread.hpp>
#include <ros/node.h>
#include <diagnostic_msgs/DiagnosticMessage.h>
+#include "ros/assert.h"
namespace robot_actions {
@@ -77,13 +78,6 @@
* @param feedback The feedback message. At the end of the function, this will be published.
*/
virtual ResultStatus execute(const Goal& goal, Feedback& feedback) = 0;
-
- /**
- * @brief Allows the user to check if the action is active. This is primarily used to condition behavior
- * for low duty cycles when the action is inactive
- * @return True if the action is active, false otherwise.
- */
- bool isActive() const { return _status.value == _status.ACTIVE; }
/**
* @brief Called by the user to check if the action has a new goal.
@@ -107,6 +101,13 @@
public:
/**
+ * @brief Allows the user to check if the action is active. This is primarily used to condition behavior
+ * for low duty cycles when the action is inactive
+ * @return True if the action is active, false otherwise.
+ */
+ bool isActive() const { return _status.value == _status.ACTIVE; }
+
+ /**
* @brief Accessor for the action name
*/
const std::string& getName() const { return _name; }
@@ -184,12 +185,12 @@
*/
Action(const std::string& name)
: _name(name), _preempt_request(false), _result_status(SUCCESS), _terminated(false), _action_thread(NULL), _callback(NULL),_diagnostics_statuses(1){
- _status.value = ActionStatus::UNDEFINED;
+ _status.value = ActionStatus::RESET;
ros::Node::instance()->advertise<diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
}
virtual ~Action(){
- terminate();
+ ROS_ASSERT_MSG(_terminated, "Actions must be terminated before they are deleted, or there will be a segfault. In this case, action '%s' terminated was terminated before it was deleted.", _name.c_str());
if(_action_thread != NULL){
_action_thread->join();
delete _action_thread;
@@ -270,8 +271,8 @@
else
diagnostics_status.message = "Active";
}
- else if (_status.value == ActionStatus::UNDEFINED)
- diagnostics_status.message = "Undefined";
+ else if (_status.value == ActionStatus::RESET)
+ diagnostics_status.message = "Reset";
else if (_status.value == ActionStatus::PREEMPTED)
diagnostics_status.message = "Preempted";
else if (_status.value == ActionStatus::ABORTED)
Modified: pkg/trunk/common/robot_actions/msg/ActionStatus.msg
===================================================================
--- pkg/trunk/common/robot_actions/msg/ActionStatus.msg 2009-06-18 00:40:41 UTC (rev 17265)
+++ pkg/trunk/common/robot_actions/msg/ActionStatus.msg 2009-06-18 00:40:41 UTC (rev 17266)
@@ -1,8 +1,8 @@
# This message defines the expected format for robot action status messages
# Embed this in the feedback state message of robot actions
-# The action is inactive, and its status with respect to a prior request is undefined.
-byte UNDEFINED=0
+# The action is inactive, and has just been reset.
+byte RESET=0
# The action has successfuly completed and is now inactive
byte SUCCESS=1
Modified: pkg/trunk/highlevel/robot_actions_tools/list_action_state.py
===================================================================
--- pkg/trunk/highlevel/robot_actions_tools/list_action_state.py 2009-06-18 00:40:41 UTC (rev 17265)
+++ pkg/trunk/highlevel/robot_actions_tools/list_action_state.py 2009-06-18 00:40:41 UTC (rev 17266)
@@ -103,8 +103,8 @@
def set_topic_key(topic, msg):
global controllers
- if (msg.status.value == msg.status.UNDEFINED):
- controllers[topic] = "Undefined"
+ if (msg.status.value == msg.status.RESET):
+ controllers[topic] = "Reset"
elif (msg.status.value == msg.status.SUCCESS):
controllers[topic] = "Success"
elif (msg.status.value == msg.status.ABORTED):
Modified: pkg/trunk/highlevel/test_robot_actions/test/utest.cc
===================================================================
--- pkg/trunk/highlevel/test_robot_actions/test/utest.cc 2009-06-18 00:40:41 UTC (rev 17265)
+++ pkg/trunk/highlevel/test_robot_actions/test/utest.cc 2009-06-18 00:40:41 UTC (rev 17266)
@@ -1,4 +1,3 @@
-#include <robot_actions/action.h>
#include <robot_actions/action_runner.h>
#include <robot_actions/action_client.h>
#include <robot_actions/message_adapter.h>
@@ -18,7 +17,7 @@
class MyAction: public robot_actions::Action<Float32, Float32> {
public:
- MyAction(): robot_actions::Action<Float32, Float32>("my_action"), _use_deactivate_wait(false) {}
+ MyAction(std::string name): robot_actions::Action<Float32, Float32>(name), _use_deactivate_wait(false) {}
bool _use_deactivate_wait;
@@ -80,7 +79,7 @@
MySimpleContainer(MyAction& action){
_value = 0;
action.connect(boost::bind(&MySimpleContainer::notify, this, _1, _2, _3));
- _status.value = robot_actions::ActionStatus::UNDEFINED;
+ _status.value = robot_actions::ActionStatus::RESET;
}
ActionStatus _status;
@@ -89,7 +88,7 @@
// Hack to fordce linkage - gtest macro issue
-const int8_t robot_actions::ActionStatus::UNDEFINED;
+const int8_t robot_actions::ActionStatus::RESET;
const int8_t robot_actions::ActionStatus::SUCCESS;
const int8_t robot_actions::ActionStatus::PREEMPTED;
const int8_t robot_actions::ActionStatus::ABORTED;
@@ -100,7 +99,7 @@
* Test - just exercises compilation and demonstrates use
*/
TEST(robot_actions, action_with_simple_container){
- MyAction a;
+ MyAction a("my_action_test_action_with_simple_container");
MySimpleContainer c(a);
Float32 g;
g.data = 10.0;
@@ -131,13 +130,14 @@
robot_actions::AbstractAdapter& abstract_adapter(adapter);
abstract_adapter.initialize();
abstract_adapter.terminate();
+ a.terminate();
}
/**
* Test - Run give a number of goals.
*/
TEST(robot_actions, many_goals) {
- MyAction a;
+ MyAction a("my_action_test_many_goals");
MySimpleContainer c(a);
Float32 g;
robot_actions::ActionStatus foo;
@@ -165,14 +165,14 @@
ASSERT_EQ(i < c._value, true);
}
}
-
+ a.terminate();
}
/**
* Test - Run give a number of goals. Use waitForDeactivation().
*/
TEST(robot_actions, many_goals_wait_for_deactivation) {
- MyAction a;
+ MyAction a("robot_actions_test_many_goals_wait_for_deactivation");
MySimpleContainer c(a);
Float32 g;
robot_actions::ActionStatus foo;
@@ -201,6 +201,7 @@
ASSERT_EQ(i < c._value, true);
}
}
+ a.terminate();
}
/**
@@ -209,7 +210,7 @@
TEST(robot_actions, action_with_action_runner){
// Now connect actions
- MyAction a;
+ MyAction a("my_action_test_action_with_action_runner");
Float32 g;
robot_actions::ActionStatus foo;
@@ -230,7 +231,7 @@
TEST(robot_actions, action_client){
// Now connect actions
- MyAction action;
+ MyAction action("my_action");
// Now run it.
robot_actions::ActionRunner runner(10.0);
@@ -244,7 +245,7 @@
Float32 g, f;
g.data = 5;
- robot_actions::ResultStatus result = client.execute(g, f, ros::Duration(1));
+ robot_actions::ResultStatus result = client.execute(g, f, ros::Duration().fromSec(10));
ASSERT_EQ(result, robot_actions::SUCCESS);
result = client.execute(g, f, ros::Duration().fromSec(0.0001));
@@ -265,7 +266,9 @@
// First allocate it with an update rate of 10 Hz
robot_actions::ActionRunner runner(10.0);
for (int i = 0; i < 100; i++) {
- MyAction* a = new MyAction();
+ std::stringstream buff;
+ buff << "my_action_test_scalability" << i;
+ MyAction* a = new MyAction(buff.str());
actions.push_back(a);
runner.connect<Float32, TestState, Float32>(*a);
}
@@ -278,6 +281,7 @@
duration.sleep();
while(!actions.size()) {
+ actions[0]->terminate();
delete actions[0];
actions.erase(actions.begin());
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|