Skip to content

Commit

Permalink
Improved the const-correctness of some actionlib classes.
Browse files Browse the repository at this point in the history
  • Loading branch information
RobertBlakeAnderson committed May 28, 2016
1 parent da39083 commit a47b10d
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 13 deletions.
6 changes: 3 additions & 3 deletions include/actionlib/client/client_goal_handle_imp.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ bool ClientGoalHandle<ActionSpec>::isExpired() const


template<class ActionSpec>
CommState ClientGoalHandle<ActionSpec>::getCommState()
CommState ClientGoalHandle<ActionSpec>::getCommState() const
{
if (!active_)
{
Expand All @@ -111,7 +111,7 @@ CommState ClientGoalHandle<ActionSpec>::getCommState()
}

template<class ActionSpec>
TerminalState ClientGoalHandle<ActionSpec>::getTerminalState()
TerminalState ClientGoalHandle<ActionSpec>::getTerminalState() const
{

if (!active_)
Expand Down Expand Up @@ -158,7 +158,7 @@ TerminalState ClientGoalHandle<ActionSpec>::getTerminalState()
}

template<class ActionSpec>
typename ClientGoalHandle<ActionSpec>::ResultConstPtr ClientGoalHandle<ActionSpec>::getResult()
typename ClientGoalHandle<ActionSpec>::ResultConstPtr ClientGoalHandle<ActionSpec>::getResult() const
{
if (!active_)
ROS_ERROR_NAMED("actionlib", "Trying to getResult on an inactive ClientGoalHandle. You are incorrectly using a ClientGoalHandle");
Expand Down
6 changes: 3 additions & 3 deletions include/actionlib/client/client_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -155,7 +155,7 @@ class ClientGoalHandle
* WAITING_FOR_CANCEL_ACK, RECALLING, PREEMPTING, DONE
* \return The current goal's communication state with the server
*/
CommState getCommState();
CommState getCommState() const;

/**
* \brief Get the terminal state information for this goal
Expand All @@ -164,14 +164,14 @@ class ClientGoalHandle
* This call only makes sense if CommState==DONE. This will send ROS_WARNs if we're not in DONE
* \return The terminal state
*/
TerminalState getTerminalState();
TerminalState getTerminalState() const;

/**
* \brief Get result associated with this goal
*
* \return NULL if no reseult received. Otherwise returns shared_ptr to result.
*/
ResultConstPtr getResult();
ResultConstPtr getResult() const;

/**
* \brief Resends this goal [with the same GoalID] to the ActionServer
Expand Down
17 changes: 10 additions & 7 deletions include/actionlib/client/simple_action_client.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include <boost/thread/condition.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/scoped_ptr.hpp>
#include <boost/concept_check.hpp>

#include "ros/ros.h"
#include "ros/callback_queue.h"
Expand All @@ -46,7 +47,6 @@
#include "actionlib/client/simple_client_goal_state.h"
#include "actionlib/client/terminal_state.h"


#ifndef DEPRECATED
#if defined(__GNUC__)
#define DEPRECATED __attribute__((deprecated))
Expand Down Expand Up @@ -124,13 +124,16 @@ class SimpleActionClient
* \param timeout Max time to block before returning. A zero timeout is interpreted as an infinite timeout.
* \return True if the server connected in the allocated time. False on timeout
*/
bool waitForServer(const ros::Duration& timeout = ros::Duration(0,0) ) { return ac_->waitForActionServerToStart(timeout); }
bool waitForServer(const ros::Duration& timeout = ros::Duration(0,0) ) const
{
return ac_->waitForActionServerToStart(timeout);
}

/**
* @brief Checks if the action client is successfully connected to the action server
* @return True if the server is connected, false otherwise
*/
bool isServerConnected()
bool isServerConnected() const
{
return ac_->isServerConnected();
}
Expand Down Expand Up @@ -175,15 +178,15 @@ class SimpleActionClient
* \brief Get the Result of the current goal
* \return shared pointer to the result. Note that this pointer will NEVER be NULL
*/
ResultConstPtr getResult();
ResultConstPtr getResult() const;

/**
* \brief Get the state information for this goal
*
* Possible States Are: PENDING, ACTIVE, RECALLED, REJECTED, PREEMPTED, ABORTED, SUCCEEDED, LOST.
* \return The goal's state. Returns LOST if this SimpleActionClient isn't tracking a goal.
*/
SimpleClientGoalState getState();
SimpleClientGoalState getState() const;

/**
* \brief Cancel all goals currently running on the action server
Expand Down Expand Up @@ -331,7 +334,7 @@ void SimpleActionClient<ActionSpec>::sendGoal(const Goal& goal,
}

template<class ActionSpec>
SimpleClientGoalState SimpleActionClient<ActionSpec>::getState()
SimpleClientGoalState SimpleActionClient<ActionSpec>::getState() const
{
if (gh_.isExpired())
{
Expand Down Expand Up @@ -395,7 +398,7 @@ SimpleClientGoalState SimpleActionClient<ActionSpec>::getState()
}

template<class ActionSpec>
typename SimpleActionClient<ActionSpec>::ResultConstPtr SimpleActionClient<ActionSpec>::getResult()
typename SimpleActionClient<ActionSpec>::ResultConstPtr SimpleActionClient<ActionSpec>::getResult() const
{
if (gh_.isExpired())
ROS_ERROR_NAMED("actionlib", "Trying to getResult() when no goal is running. You are incorrectly using SimpleActionClient");
Expand Down
8 changes: 8 additions & 0 deletions include/actionlib/managed_list.h
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,8 @@ class ManagedList
iterator() { }
T& operator*() { return it_->elem; }
T& operator->() { return it_->elem; }
const T& operator*() const { return it_->elem; }
const T& operator->() const { return it_->elem; }
bool operator==(const iterator& rhs) const { return it_ == rhs.it_; }
bool operator!=(const iterator& rhs) const { return !(*this == rhs); }
void operator++() { it_++; }
Expand Down Expand Up @@ -154,6 +156,12 @@ class ManagedList
assert(valid_);
return *it_;
}

const T& getElem() const
{
assert(valid_);
return *it_;
}

/**
* \brief Checks if two handles point to the same list elem
Expand Down

0 comments on commit a47b10d

Please sign in to comment.