Skip to content

Commit

Permalink
fixing C++ comments
Browse files Browse the repository at this point in the history
  • Loading branch information
mgonzs13 committed Nov 4, 2024
1 parent e27d5cb commit 691496f
Show file tree
Hide file tree
Showing 6 changed files with 58 additions and 41 deletions.
7 changes: 4 additions & 3 deletions yasmin/include/yasmin/blackboard/blackboard.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,10 @@ namespace blackboard {
*/
class Blackboard {
private:
std::recursive_mutex mutex; ///< Mutex for thread safety.
std::map<std::string, BlackboardValueInterface *>
values; ///< Storage for key-value pairs.
/// Mutex for thread safety.
std::recursive_mutex mutex;
/// Storage for key-value pairs.
std::map<std::string, BlackboardValueInterface *> values;

public:
/** @brief Default constructor for Blackboard. */
Expand Down
2 changes: 1 addition & 1 deletion yasmin/include/yasmin/cb_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ namespace yasmin {
class CbState : public State {

private:
/** Pointer to the callback function to be executed. */
/// Pointer to the callback function to be executed.
std::string (*callback)(std::shared_ptr<blackboard::Blackboard> blackboard);

public:
Expand Down
3 changes: 2 additions & 1 deletion yasmin/include/yasmin/state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,8 @@ namespace yasmin {
class State {

protected:
std::set<std::string> outcomes; ///< The possible outcomes of this state.
/// The possible outcomes of this state.
std::set<std::string> outcomes;

private:
/// Indicates if the state has been canceled.
Expand Down
4 changes: 2 additions & 2 deletions yasmin_demos/src/monitor_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,8 @@ class PrintOdometryState
: public yasmin_ros::MonitorState<nav_msgs::msg::Odometry> {

public:
int times; ///< The number of times the state will print odometry data before
///< transitioning.
/// The number of times the state will process messages
int times;

/**
* @brief Constructor for the PrintOdometryState class.
Expand Down
63 changes: 37 additions & 26 deletions yasmin_ros/include/yasmin_ros/action_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,32 +295,43 @@ template <typename ActionT> class ActionState : public yasmin::State {
}

private:
rclcpp::Node::SharedPtr node_; ///< Shared pointer to the ROS 2 node.

std::string action_name; ///< Name of the action to communicate with.

ActionClient action_client; ///< Shared pointer to the action client.
std::condition_variable
action_done_cond; ///< Condition variable for action completion.
std::mutex action_done_mutex; ///< Mutex for protecting action completion.
std::condition_variable
action_cancel_cond; ///< Condition variable for action cancellation.
std::mutex action_cancel_mutex; ///< Mutex for protecting action cancellation.

Result action_result; ///< Shared pointer to the action result.
rclcpp_action::ResultCode action_status; ///< Status of the action execution.

std::shared_ptr<GoalHandle> goal_handle; ///< Handle for the current goal.
std::mutex
goal_handle_mutex; ///< Mutex for protecting access to the goal handle.

CreateGoalHandler
create_goal_handler; ///< Handler function for creating goals.
ResultHandler result_handler; ///< Handler function for processing results.
FeedbackHandler
feedback_handler; ///< Handler function for processing feedback.

int timeout; ///< Maximum time to wait for the action server.
/// Shared pointer to the ROS 2 node.
rclcpp::Node::SharedPtr node_;

/// Name of the action to communicate with.
std::string action_name;

/// Shared pointer to the action client.
ActionClient action_client;
/// Condition variable for action completion.
std::condition_variable action_done_cond;

/// Mutex for protecting action completion.
std::mutex action_done_mutex;
/// Condition variable for action cancellation.
std::condition_variable action_cancel_cond;
/// Mutex for protecting action cancellation.
std::mutex action_cancel_mutex;

/// Shared pointer to the action result.
Result action_result;
/// Status of the action execution.
rclcpp_action::ResultCode action_status;

/// Handle for the current goal.
std::shared_ptr<GoalHandle> goal_handle;
/// Mutex for protecting access to the goal handle.
std::mutex goal_handle_mutex;

/// Handler function for creating goals.
CreateGoalHandler create_goal_handler;
/// Handler function for processing results.
ResultHandler result_handler;
/// Handler function for processing feedback.
FeedbackHandler feedback_handler;

/// Maximum time to wait for the action server.
int timeout;

#if defined(FOXY)
/**
Expand Down
20 changes: 12 additions & 8 deletions yasmin_ros/include/yasmin_ros/service_state.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,14 +186,18 @@ template <typename ServiceT> class ServiceState : public yasmin::State {
}

private:
rclcpp::Node::SharedPtr node_; ///< Shared pointer to the ROS 2 node.
std::shared_ptr<rclcpp::Client<ServiceT>>
service_client; ///< Shared pointer to the service client.
CreateRequestHandler
create_request_handler; ///< Function to create service requests.
ResponseHandler response_handler; ///< Function to handle service responses.
std::string srv_name; ///< Name of the service.
int timeout; ///< Maximum wait time for service availability.
/// Shared pointer to the ROS 2 node
rclcpp::Node::SharedPtr node_;
/// Shared pointer to the service client.
std::shared_ptr<rclcpp::Client<ServiceT>> service_client;
/// Function to create service requests.
CreateRequestHandler create_request_handler;
/// Function to handle service responses.
ResponseHandler response_handler;
/// Name of the service.
std::string srv_name;
/// Maximum wait time for service availability.
int timeout;

/**
* @brief Create a service request based on the blackboard.
Expand Down

0 comments on commit 691496f

Please sign in to comment.