SMACC2
Public Types | Public Member Functions | Public Attributes | List of all members
LEDActionServer Class Reference
Inheritance diagram for LEDActionServer:
Inheritance graph
Collaboration diagram for LEDActionServer:
Collaboration graph

Public Types

using GoalHandleLEDControl = rclcpp_action::ServerGoalHandle< sm_dance_bot::action::LEDControl >
 
using GoalHandleLEDControl = rclcpp_action::ServerGoalHandle< sm_dance_bot_strikes_back::action::LEDControl >
 
using GoalHandleLEDControl = rclcpp_action::ServerGoalHandle< sm_dance_bot_warehouse::action::LEDControl >
 
using GoalHandleLEDControl = rclcpp_action::ServerGoalHandle< sm_dance_bot_warehouse_2::action::LEDControl >
 
using GoalHandleLEDControl = rclcpp_action::ServerGoalHandle< sm_dance_bot_warehouse_3::action::LEDControl >
 

Public Member Functions

 LEDActionServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 
void execute (const std::shared_ptr< GoalHandleLEDControl > gh)
 
rclcpp_action::GoalResponse handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const sm_dance_bot::action::LEDControl::Goal >)
 
rclcpp_action::CancelResponse handle_cancel (const std::shared_ptr< GoalHandleLEDControl >)
 
void handle_accepted (const std::shared_ptr< GoalHandleLEDControl > goal_handle)
 
void run ()
 
void publishStateMarker ()
 
 LEDActionServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 
void execute (const std::shared_ptr< GoalHandleLEDControl > gh)
 
rclcpp_action::GoalResponse handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const sm_dance_bot_strikes_back::action::LEDControl::Goal >)
 
rclcpp_action::CancelResponse handle_cancel (const std::shared_ptr< GoalHandleLEDControl >)
 
void handle_accepted (const std::shared_ptr< GoalHandleLEDControl > goal_handle)
 
void run ()
 
void publishStateMarker ()
 
 LEDActionServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 
void execute (const std::shared_ptr< GoalHandleLEDControl > gh)
 
rclcpp_action::GoalResponse handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const sm_dance_bot_warehouse::action::LEDControl::Goal >)
 
rclcpp_action::CancelResponse handle_cancel (const std::shared_ptr< GoalHandleLEDControl >)
 
void handle_accepted (const std::shared_ptr< GoalHandleLEDControl > goal_handle)
 
void run ()
 
void publishStateMarker ()
 
 LEDActionServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 
void execute (const std::shared_ptr< GoalHandleLEDControl > gh)
 
rclcpp_action::GoalResponse handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const sm_dance_bot_warehouse_2::action::LEDControl::Goal >)
 
rclcpp_action::CancelResponse handle_cancel (const std::shared_ptr< GoalHandleLEDControl >)
 
void handle_accepted (const std::shared_ptr< GoalHandleLEDControl > goal_handle)
 
void run ()
 
void publishStateMarker ()
 
 LEDActionServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 
void execute (const std::shared_ptr< GoalHandleLEDControl > gh)
 
rclcpp_action::GoalResponse handle_goal (const rclcpp_action::GoalUUID &, std::shared_ptr< const sm_dance_bot_warehouse_3::action::LEDControl::Goal >)
 
rclcpp_action::CancelResponse handle_cancel (const std::shared_ptr< GoalHandleLEDControl >)
 
void handle_accepted (const std::shared_ptr< GoalHandleLEDControl > goal_handle)
 
void run ()
 
void publishStateMarker ()
 

Public Attributes

std::shared_ptr< rclcpp_action::Server< sm_dance_bot::action::LEDControl > > as_
 
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr stateMarkerPublisher_
 
uint8_t cmd
 
uint8_t currentState_
 
std::shared_ptr< rclcpp_action::Server< sm_dance_bot_strikes_back::action::LEDControl > > as_
 
std::shared_ptr< rclcpp_action::Server< sm_dance_bot_warehouse::action::LEDControl > > as_
 
std::shared_ptr< rclcpp_action::Server< sm_dance_bot_warehouse_2::action::LEDControl > > as_
 
std::shared_ptr< rclcpp_action::Server< sm_dance_bot_warehouse_3::action::LEDControl > > as_
 

Detailed Description

Definition at line 39 of file led_action_server_node.cpp.

Member Typedef Documentation

◆ GoalHandleLEDControl [1/5]

using LEDActionServer::GoalHandleLEDControl = rclcpp_action::ServerGoalHandle<sm_dance_bot::action::LEDControl>

Definition at line 43 of file led_action_server_node.cpp.

◆ GoalHandleLEDControl [2/5]

using LEDActionServer::GoalHandleLEDControl = rclcpp_action::ServerGoalHandle<sm_dance_bot_strikes_back::action::LEDControl>

Definition at line 43 of file led_action_server_node.cpp.

◆ GoalHandleLEDControl [3/5]

using LEDActionServer::GoalHandleLEDControl = rclcpp_action::ServerGoalHandle<sm_dance_bot_warehouse::action::LEDControl>

Definition at line 43 of file led_action_server_node.cpp.

◆ GoalHandleLEDControl [4/5]

using LEDActionServer::GoalHandleLEDControl = rclcpp_action::ServerGoalHandle<sm_dance_bot_warehouse_2::action::LEDControl>

Definition at line 43 of file led_action_server_node.cpp.

◆ GoalHandleLEDControl [5/5]

using LEDActionServer::GoalHandleLEDControl = rclcpp_action::ServerGoalHandle<sm_dance_bot_warehouse_3::action::LEDControl>

Definition at line 43 of file led_action_server_node.cpp.

Constructor & Destructor Documentation

◆ LEDActionServer() [1/5]

LEDActionServer::LEDActionServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
inline

constructor()

Definition at line 57 of file led_action_server_node.cpp.

58 : Node("led_action_server_node", options)
59 {
60 currentState_ = sm_dance_bot::action::LEDControl::Result::STATE_UNKNOWN;
61 }

References currentState_.

◆ LEDActionServer() [2/5]

LEDActionServer::LEDActionServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
inline

constructor()

Definition at line 57 of file led_action_server_node.cpp.

58 : Node("led_action_server_node", options)
59 {
60 currentState_ = sm_dance_bot_strikes_back::action::LEDControl::Result::STATE_UNKNOWN;
61 }

References currentState_.

◆ LEDActionServer() [3/5]

LEDActionServer::LEDActionServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
inline

constructor()

Definition at line 57 of file led_action_server_node.cpp.

58 : Node("led_action_server_node", options)
59 {
60 currentState_ = sm_dance_bot_warehouse::action::LEDControl::Result::STATE_UNKNOWN;
61 }

References currentState_.

◆ LEDActionServer() [4/5]

LEDActionServer::LEDActionServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
inline

constructor()

Definition at line 57 of file led_action_server_node.cpp.

58 : Node("led_action_server_node", options)
59 {
60 currentState_ = sm_dance_bot_warehouse_2::action::LEDControl::Result::STATE_UNKNOWN;
61 }

References currentState_.

◆ LEDActionServer() [5/5]

LEDActionServer::LEDActionServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
inline

constructor()

Definition at line 57 of file led_action_server_node.cpp.

58 : Node("led_action_server_node", options)
59 {
60 currentState_ = sm_dance_bot_warehouse_3::action::LEDControl::Result::STATE_UNKNOWN;
61 }

References currentState_.

Member Function Documentation

◆ execute() [1/5]

void LEDActionServer::execute ( const std::shared_ptr< GoalHandleLEDControl gh)
inline

execute()

Definition at line 68 of file led_action_server_node.cpp.

70 {
71 auto goal = gh->get_goal();
72 RCLCPP_INFO_STREAM(get_logger(), "Tool action server request: " << goal->command);
73
74 cmd = goal->command;
75
76 if (goal->command == sm_dance_bot::action::LEDControl_Goal::CMD_ON)
77 {
78 RCLCPP_INFO(this->get_logger(), "ON");
79 currentState_ = sm_dance_bot::action::LEDControl_Result::STATE_RUNNING;
80 }
81 else if (goal->command == sm_dance_bot::action::LEDControl_Goal::CMD_OFF)
82 {
83 RCLCPP_INFO(this->get_logger(), "OFF");
84 currentState_ = sm_dance_bot::action::LEDControl_Result::STATE_IDLE;
85 }
86
87 auto feedback_msg = std::make_shared<sm_dance_bot::action::LEDControl::Feedback>();
88
89 // 10Hz internal loop
90 rclcpp::Rate rate(20);
91
92 while (rclcpp::ok())
93 {
94 gh->publish_feedback(feedback_msg);
95
97 rate.sleep();
98 RCLCPP_INFO_THROTTLE(this->get_logger(), *(this->get_clock()), 2000, "Loop feedback");
99 }
100
101 auto result = std::make_shared<sm_dance_bot::action::LEDControl::Result>();
102 result->state = this->currentState_;
103
104 // never reach succeeded because were are interested in keeping the feedback alive
105 //as_->setSucceeded();
106 gh->succeed(result);
107 }

References cmd, currentState_, and publishStateMarker().

Referenced by handle_accepted().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ execute() [2/5]

void LEDActionServer::execute ( const std::shared_ptr< GoalHandleLEDControl gh)
inline

execute()

Definition at line 68 of file led_action_server_node.cpp.

70 {
71 auto goal = gh->get_goal();
72 RCLCPP_INFO_STREAM(get_logger(), "Tool action server request: " << goal->command);
73
74 cmd = goal->command;
75
76 if (goal->command == sm_dance_bot_strikes_back::action::LEDControl_Goal::CMD_ON)
77 {
78 RCLCPP_INFO(this->get_logger(), "ON");
79 currentState_ = sm_dance_bot_strikes_back::action::LEDControl_Result::STATE_RUNNING;
80 }
81 else if (goal->command == sm_dance_bot_strikes_back::action::LEDControl_Goal::CMD_OFF)
82 {
83 RCLCPP_INFO(this->get_logger(), "OFF");
84 currentState_ = sm_dance_bot_strikes_back::action::LEDControl_Result::STATE_IDLE;
85 }
86
87 auto feedback_msg = std::make_shared<sm_dance_bot_strikes_back::action::LEDControl::Feedback>();
88
89 // 10Hz internal loop
90 rclcpp::Rate rate(20);
91
92 while (rclcpp::ok())
93 {
94 gh->publish_feedback(feedback_msg);
95
97 rate.sleep();
98 RCLCPP_INFO_THROTTLE(this->get_logger(), *(this->get_clock()), 2000, "Loop feedback");
99 }
100
101 auto result = std::make_shared<sm_dance_bot_strikes_back::action::LEDControl::Result>();
102 result->state = this->currentState_;
103
104 // never reach succeeded because were are interested in keeping the feedback alive
105 //as_->setSucceeded();
106 gh->succeed(result);
107 }

References cmd, currentState_, and publishStateMarker().

Here is the call graph for this function:

◆ execute() [3/5]

void LEDActionServer::execute ( const std::shared_ptr< GoalHandleLEDControl gh)
inline

execute()

Definition at line 68 of file led_action_server_node.cpp.

70 {
71 auto goal = gh->get_goal();
72 RCLCPP_INFO_STREAM(get_logger(), "Tool action server request: " << goal->command);
73
74 cmd = goal->command;
75
76 if (goal->command == sm_dance_bot_warehouse::action::LEDControl_Goal::CMD_ON)
77 {
78 RCLCPP_INFO(this->get_logger(), "ON");
79 currentState_ = sm_dance_bot_warehouse::action::LEDControl_Result::STATE_RUNNING;
80 }
81 else if (goal->command == sm_dance_bot_warehouse::action::LEDControl_Goal::CMD_OFF)
82 {
83 RCLCPP_INFO(this->get_logger(), "OFF");
84 currentState_ = sm_dance_bot_warehouse::action::LEDControl_Result::STATE_IDLE;
85 }
86
87 auto feedback_msg = std::make_shared<sm_dance_bot_warehouse::action::LEDControl::Feedback>();
88
89 // 10Hz internal loop
90 rclcpp::Rate rate(20);
91
92 while (rclcpp::ok())
93 {
94 gh->publish_feedback(feedback_msg);
95
97 rate.sleep();
98 RCLCPP_INFO_THROTTLE(this->get_logger(), *(this->get_clock()), 2000, "Loop feedback");
99 }
100
101 auto result = std::make_shared<sm_dance_bot_warehouse::action::LEDControl::Result>();
102 result->state = this->currentState_;
103
104 // never reach succeeded because were are interested in keeping the feedback alive
105 //as_->setSucceeded();
106 gh->succeed(result);
107 }

References cmd, currentState_, and publishStateMarker().

Here is the call graph for this function:

◆ execute() [4/5]

void LEDActionServer::execute ( const std::shared_ptr< GoalHandleLEDControl gh)
inline

execute()

Definition at line 68 of file led_action_server_node.cpp.

70 {
71 auto goal = gh->get_goal();
72 RCLCPP_INFO_STREAM(get_logger(), "Tool action server request: " << goal->command);
73
74 cmd = goal->command;
75
76 if (goal->command == sm_dance_bot_warehouse_2::action::LEDControl_Goal::CMD_ON)
77 {
78 RCLCPP_INFO(this->get_logger(), "ON");
79 currentState_ = sm_dance_bot_warehouse_2::action::LEDControl_Result::STATE_RUNNING;
80 }
81 else if (goal->command == sm_dance_bot_warehouse_2::action::LEDControl_Goal::CMD_OFF)
82 {
83 RCLCPP_INFO(this->get_logger(), "OFF");
84 currentState_ = sm_dance_bot_warehouse_2::action::LEDControl_Result::STATE_IDLE;
85 }
86
87 auto feedback_msg = std::make_shared<sm_dance_bot_warehouse_2::action::LEDControl::Feedback>();
88
89 // 10Hz internal loop
90 rclcpp::Rate rate(20);
91
92 while (rclcpp::ok())
93 {
94 gh->publish_feedback(feedback_msg);
95
97 rate.sleep();
98 RCLCPP_INFO_THROTTLE(this->get_logger(), *(this->get_clock()), 2000, "Loop feedback");
99 }
100
101 auto result = std::make_shared<sm_dance_bot_warehouse_2::action::LEDControl::Result>();
102 result->state = this->currentState_;
103
104 // never reach succeeded because were are interested in keeping the feedback alive
105 //as_->setSucceeded();
106 gh->succeed(result);
107 }

References cmd, currentState_, and publishStateMarker().

Here is the call graph for this function:

◆ execute() [5/5]

void LEDActionServer::execute ( const std::shared_ptr< GoalHandleLEDControl gh)
inline

execute()

Definition at line 68 of file led_action_server_node.cpp.

70 {
71 auto goal = gh->get_goal();
72 RCLCPP_INFO_STREAM(get_logger(), "Tool action server request: " << goal->command);
73
74 cmd = goal->command;
75
76 if (goal->command == sm_dance_bot_warehouse_3::action::LEDControl_Goal::CMD_ON)
77 {
78 RCLCPP_INFO(this->get_logger(), "ON");
79 currentState_ = sm_dance_bot_warehouse_3::action::LEDControl_Result::STATE_RUNNING;
80 }
81 else if (goal->command == sm_dance_bot_warehouse_3::action::LEDControl_Goal::CMD_OFF)
82 {
83 RCLCPP_INFO(this->get_logger(), "OFF");
84 currentState_ = sm_dance_bot_warehouse_3::action::LEDControl_Result::STATE_IDLE;
85 }
86
87 auto feedback_msg = std::make_shared<sm_dance_bot_warehouse_3::action::LEDControl::Feedback>();
88
89 // 10Hz internal loop
90 rclcpp::Rate rate(20);
91
92 while (rclcpp::ok())
93 {
94 gh->publish_feedback(feedback_msg);
95
97 rate.sleep();
98 RCLCPP_INFO_THROTTLE(this->get_logger(), *(this->get_clock()), 2000, "Loop feedback");
99 }
100
101 auto result = std::make_shared<sm_dance_bot_warehouse_3::action::LEDControl::Result>();
102 result->state = this->currentState_;
103
104 // never reach succeeded because were are interested in keeping the feedback alive
105 //as_->setSucceeded();
106 gh->succeed(result);
107 }

References cmd, currentState_, and publishStateMarker().

Here is the call graph for this function:

◆ handle_accepted() [1/5]

void LEDActionServer::handle_accepted ( const std::shared_ptr< GoalHandleLEDControl goal_handle)
inline

Definition at line 132 of file led_action_server_node.cpp.

133 {
134 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
135 std::thread{std::bind(&LEDActionServer::execute, this, std::placeholders::_1), goal_handle}
136 .detach();
137 }
void execute(const std::shared_ptr< GoalHandleLEDControl > gh)

References execute().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_accepted() [2/5]

void LEDActionServer::handle_accepted ( const std::shared_ptr< GoalHandleLEDControl goal_handle)
inline

Definition at line 132 of file led_action_server_node.cpp.

133 {
134 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
135 std::thread{std::bind(&LEDActionServer::execute, this, std::placeholders::_1), goal_handle}
136 .detach();
137 }

References execute().

Here is the call graph for this function:

◆ handle_accepted() [3/5]

void LEDActionServer::handle_accepted ( const std::shared_ptr< GoalHandleLEDControl goal_handle)
inline

Definition at line 132 of file led_action_server_node.cpp.

133 {
134 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
135 std::thread{std::bind(&LEDActionServer::execute, this, std::placeholders::_1), goal_handle}
136 .detach();
137 }

References execute().

Here is the call graph for this function:

◆ handle_accepted() [4/5]

void LEDActionServer::handle_accepted ( const std::shared_ptr< GoalHandleLEDControl goal_handle)
inline

Definition at line 132 of file led_action_server_node.cpp.

133 {
134 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
135 std::thread{std::bind(&LEDActionServer::execute, this, std::placeholders::_1), goal_handle}
136 .detach();
137 }

References execute().

Here is the call graph for this function:

◆ handle_accepted() [5/5]

void LEDActionServer::handle_accepted ( const std::shared_ptr< GoalHandleLEDControl goal_handle)
inline

Definition at line 132 of file led_action_server_node.cpp.

133 {
134 // this needs to return quickly to avoid blocking the executor, so spin up a new thread
135 std::thread{std::bind(&LEDActionServer::execute, this, std::placeholders::_1), goal_handle}
136 .detach();
137 }

References execute().

Here is the call graph for this function:

◆ handle_cancel() [1/5]

rclcpp_action::CancelResponse LEDActionServer::handle_cancel ( const std::shared_ptr< GoalHandleLEDControl )
inline

Definition at line 124 of file led_action_server_node.cpp.

126 {
127 RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal");
128 //(void)goal_handle;
129 return rclcpp_action::CancelResponse::ACCEPT;
130 }

Referenced by run().

Here is the caller graph for this function:

◆ handle_cancel() [2/5]

rclcpp_action::CancelResponse LEDActionServer::handle_cancel ( const std::shared_ptr< GoalHandleLEDControl )
inline

Definition at line 124 of file led_action_server_node.cpp.

126 {
127 RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal");
128 //(void)goal_handle;
129 return rclcpp_action::CancelResponse::ACCEPT;
130 }

◆ handle_cancel() [3/5]

rclcpp_action::CancelResponse LEDActionServer::handle_cancel ( const std::shared_ptr< GoalHandleLEDControl )
inline

Definition at line 124 of file led_action_server_node.cpp.

126 {
127 RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal");
128 //(void)goal_handle;
129 return rclcpp_action::CancelResponse::ACCEPT;
130 }

◆ handle_cancel() [4/5]

rclcpp_action::CancelResponse LEDActionServer::handle_cancel ( const std::shared_ptr< GoalHandleLEDControl )
inline

Definition at line 124 of file led_action_server_node.cpp.

126 {
127 RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal");
128 //(void)goal_handle;
129 return rclcpp_action::CancelResponse::ACCEPT;
130 }

◆ handle_cancel() [5/5]

rclcpp_action::CancelResponse LEDActionServer::handle_cancel ( const std::shared_ptr< GoalHandleLEDControl )
inline

Definition at line 124 of file led_action_server_node.cpp.

126 {
127 RCLCPP_INFO(rclcpp::get_logger("server"), "Got request to cancel goal");
128 //(void)goal_handle;
129 return rclcpp_action::CancelResponse::ACCEPT;
130 }

◆ handle_goal() [1/5]

rclcpp_action::GoalResponse LEDActionServer::handle_goal ( const rclcpp_action::GoalUUID &  ,
std::shared_ptr< const sm_dance_bot::action::LEDControl::Goal >   
)
inline

Definition at line 109 of file led_action_server_node.cpp.

112 {
113 // (void)uuid;
114 // // Let's reject sequences that are over 9000
115 // if (goal->order > 9000) {
116 // return rclcpp_action::GoalResponse::REJECT;
117 // }
118
119 // lets accept everything
120 RCLCPP_INFO(this->get_logger(), "Handle goal");
121 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
122 }

Referenced by run().

Here is the caller graph for this function:

◆ handle_goal() [2/5]

rclcpp_action::GoalResponse LEDActionServer::handle_goal ( const rclcpp_action::GoalUUID &  ,
std::shared_ptr< const sm_dance_bot_strikes_back::action::LEDControl::Goal >   
)
inline

Definition at line 109 of file led_action_server_node.cpp.

112 {
113 // (void)uuid;
114 // // Let's reject sequences that are over 9000
115 // if (goal->order > 9000) {
116 // return rclcpp_action::GoalResponse::REJECT;
117 // }
118
119 // lets accept everything
120 RCLCPP_INFO(this->get_logger(), "Handle goal");
121 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
122 }

◆ handle_goal() [3/5]

rclcpp_action::GoalResponse LEDActionServer::handle_goal ( const rclcpp_action::GoalUUID &  ,
std::shared_ptr< const sm_dance_bot_warehouse::action::LEDControl::Goal >   
)
inline

Definition at line 109 of file led_action_server_node.cpp.

112 {
113 // (void)uuid;
114 // // Let's reject sequences that are over 9000
115 // if (goal->order > 9000) {
116 // return rclcpp_action::GoalResponse::REJECT;
117 // }
118
119 // lets accept everything
120 RCLCPP_INFO(this->get_logger(), "Handle goal");
121 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
122 }

◆ handle_goal() [4/5]

rclcpp_action::GoalResponse LEDActionServer::handle_goal ( const rclcpp_action::GoalUUID &  ,
std::shared_ptr< const sm_dance_bot_warehouse_2::action::LEDControl::Goal >   
)
inline

Definition at line 109 of file led_action_server_node.cpp.

112 {
113 // (void)uuid;
114 // // Let's reject sequences that are over 9000
115 // if (goal->order > 9000) {
116 // return rclcpp_action::GoalResponse::REJECT;
117 // }
118
119 // lets accept everything
120 RCLCPP_INFO(this->get_logger(), "Handle goal");
121 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
122 }

◆ handle_goal() [5/5]

rclcpp_action::GoalResponse LEDActionServer::handle_goal ( const rclcpp_action::GoalUUID &  ,
std::shared_ptr< const sm_dance_bot_warehouse_3::action::LEDControl::Goal >   
)
inline

Definition at line 109 of file led_action_server_node.cpp.

112 {
113 // (void)uuid;
114 // // Let's reject sequences that are over 9000
115 // if (goal->order > 9000) {
116 // return rclcpp_action::GoalResponse::REJECT;
117 // }
118
119 // lets accept everything
120 RCLCPP_INFO(this->get_logger(), "Handle goal");
121 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
122 }

◆ publishStateMarker() [1/5]

void LEDActionServer::publishStateMarker ( )
inline

publishStateMarker()

Definition at line 165 of file led_action_server_node.cpp.

166 {
167 visualization_msgs::msg::Marker marker;
168 marker.header.frame_id = "base_link";
169 marker.header.stamp = this->now();
170
171 marker.ns = "tool_namespace";
172 marker.id = 0;
173 marker.type = visualization_msgs::msg::Marker::SPHERE;
174 marker.action = visualization_msgs::msg::Marker::ADD;
175
176 marker.scale.x = 0.2;
177 marker.scale.y = 0.2;
178 marker.scale.z = 0.2;
179
180 marker.color.a = 1;
181
182 if (currentState_ == sm_dance_bot::action::LEDControl::Result::STATE_RUNNING)
183 {
184 // show green ball
185 marker.color.r = 0;
186 marker.color.g = 1;
187 marker.color.b = 0;
188 }
189 else if (currentState_ == sm_dance_bot::action::LEDControl::Result::STATE_IDLE)
190 {
191 // show gray ball
192 marker.color.r = 0.7;
193 marker.color.g = 0.7;
194 marker.color.b = 0.7;
195 }
196 else
197 {
198 // show black ball
199 marker.color.r = 0;
200 marker.color.g = 0;
201 marker.color.b = 0;
202 }
203
204 marker.pose.orientation.w = 1;
205 marker.pose.position.x = 0;
206 marker.pose.position.y = 0;
207 marker.pose.position.z = 1;
208
209 visualization_msgs::msg::MarkerArray ma;
210 ma.markers.push_back(marker);
211
212 stateMarkerPublisher_->publish(ma);
213 }
rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr stateMarkerPublisher_

References currentState_, and stateMarkerPublisher_.

Referenced by execute().

Here is the caller graph for this function:

◆ publishStateMarker() [2/5]

void LEDActionServer::publishStateMarker ( )
inline

publishStateMarker()

Definition at line 165 of file led_action_server_node.cpp.

166 {
167 visualization_msgs::msg::Marker marker;
168 marker.header.frame_id = "base_link";
169 marker.header.stamp = this->now();
170
171 marker.ns = "tool_namespace";
172 marker.id = 0;
173 marker.type = visualization_msgs::msg::Marker::SPHERE;
174 marker.action = visualization_msgs::msg::Marker::ADD;
175
176 marker.scale.x = 0.2;
177 marker.scale.y = 0.2;
178 marker.scale.z = 0.2;
179
180 marker.color.a = 1;
181
182 if (currentState_ == sm_dance_bot_strikes_back::action::LEDControl::Result::STATE_RUNNING)
183 {
184 // show green ball
185 marker.color.r = 0;
186 marker.color.g = 1;
187 marker.color.b = 0;
188 }
189 else if (currentState_ == sm_dance_bot_strikes_back::action::LEDControl::Result::STATE_IDLE)
190 {
191 // show gray ball
192 marker.color.r = 0.7;
193 marker.color.g = 0.7;
194 marker.color.b = 0.7;
195 }
196 else
197 {
198 // show black ball
199 marker.color.r = 0;
200 marker.color.g = 0;
201 marker.color.b = 0;
202 }
203
204 marker.pose.orientation.w = 1;
205 marker.pose.position.x = 0;
206 marker.pose.position.y = 0;
207 marker.pose.position.z = 1;
208
209 visualization_msgs::msg::MarkerArray ma;
210 ma.markers.push_back(marker);
211
212 stateMarkerPublisher_->publish(ma);
213 }

References currentState_, and stateMarkerPublisher_.

◆ publishStateMarker() [3/5]

void LEDActionServer::publishStateMarker ( )
inline

publishStateMarker()

Definition at line 165 of file led_action_server_node.cpp.

166 {
167 visualization_msgs::msg::Marker marker;
168 marker.header.frame_id = "base_link";
169 marker.header.stamp = this->now();
170
171 marker.ns = "tool_namespace";
172 marker.id = 0;
173 marker.type = visualization_msgs::msg::Marker::SPHERE;
174 marker.action = visualization_msgs::msg::Marker::ADD;
175
176 marker.scale.x = 0.2;
177 marker.scale.y = 0.2;
178 marker.scale.z = 0.2;
179
180 marker.color.a = 1;
181
182 if (currentState_ == sm_dance_bot_warehouse::action::LEDControl::Result::STATE_RUNNING)
183 {
184 // show green ball
185 marker.color.r = 0;
186 marker.color.g = 1;
187 marker.color.b = 0;
188 }
189 else if (currentState_ == sm_dance_bot_warehouse::action::LEDControl::Result::STATE_IDLE)
190 {
191 // show gray ball
192 marker.color.r = 0.7;
193 marker.color.g = 0.7;
194 marker.color.b = 0.7;
195 }
196 else
197 {
198 // show black ball
199 marker.color.r = 0;
200 marker.color.g = 0;
201 marker.color.b = 0;
202 }
203
204 marker.pose.orientation.w = 1;
205 marker.pose.position.x = 0;
206 marker.pose.position.y = 0;
207 marker.pose.position.z = 1;
208
209 visualization_msgs::msg::MarkerArray ma;
210 ma.markers.push_back(marker);
211
212 stateMarkerPublisher_->publish(ma);
213 }

References currentState_, and stateMarkerPublisher_.

◆ publishStateMarker() [4/5]

void LEDActionServer::publishStateMarker ( )
inline

publishStateMarker()

Definition at line 165 of file led_action_server_node.cpp.

166 {
167 visualization_msgs::msg::Marker marker;
168 marker.header.frame_id = "base_link";
169 marker.header.stamp = this->now();
170
171 marker.ns = "tool_namespace";
172 marker.id = 0;
173 marker.type = visualization_msgs::msg::Marker::SPHERE;
174 marker.action = visualization_msgs::msg::Marker::ADD;
175
176 marker.scale.x = 0.2;
177 marker.scale.y = 0.2;
178 marker.scale.z = 0.2;
179
180 marker.color.a = 1;
181
182 if (currentState_ == sm_dance_bot_warehouse_2::action::LEDControl::Result::STATE_RUNNING)
183 {
184 // show green ball
185 marker.color.r = 0;
186 marker.color.g = 1;
187 marker.color.b = 0;
188 }
189 else if (currentState_ == sm_dance_bot_warehouse_2::action::LEDControl::Result::STATE_IDLE)
190 {
191 // show gray ball
192 marker.color.r = 0.7;
193 marker.color.g = 0.7;
194 marker.color.b = 0.7;
195 }
196 else
197 {
198 // show black ball
199 marker.color.r = 0;
200 marker.color.g = 0;
201 marker.color.b = 0;
202 }
203
204 marker.pose.orientation.w = 1;
205 marker.pose.position.x = 0;
206 marker.pose.position.y = 0;
207 marker.pose.position.z = 1;
208
209 visualization_msgs::msg::MarkerArray ma;
210 ma.markers.push_back(marker);
211
212 stateMarkerPublisher_->publish(ma);
213 }

References currentState_, and stateMarkerPublisher_.

◆ publishStateMarker() [5/5]

void LEDActionServer::publishStateMarker ( )
inline

publishStateMarker()

Definition at line 165 of file led_action_server_node.cpp.

166 {
167 visualization_msgs::msg::Marker marker;
168 marker.header.frame_id = "base_link";
169 marker.header.stamp = this->now();
170
171 marker.ns = "tool_namespace";
172 marker.id = 0;
173 marker.type = visualization_msgs::msg::Marker::SPHERE;
174 marker.action = visualization_msgs::msg::Marker::ADD;
175
176 marker.scale.x = 0.2;
177 marker.scale.y = 0.2;
178 marker.scale.z = 0.2;
179
180 marker.color.a = 1;
181
182 if (currentState_ == sm_dance_bot_warehouse_3::action::LEDControl::Result::STATE_RUNNING)
183 {
184 // show green ball
185 marker.color.r = 0;
186 marker.color.g = 1;
187 marker.color.b = 0;
188 }
189 else if (currentState_ == sm_dance_bot_warehouse_3::action::LEDControl::Result::STATE_IDLE)
190 {
191 // show gray ball
192 marker.color.r = 0.7;
193 marker.color.g = 0.7;
194 marker.color.b = 0.7;
195 }
196 else
197 {
198 // show black ball
199 marker.color.r = 0;
200 marker.color.g = 0;
201 marker.color.b = 0;
202 }
203
204 marker.pose.orientation.w = 1;
205 marker.pose.position.x = 0;
206 marker.pose.position.y = 0;
207 marker.pose.position.z = 1;
208
209 visualization_msgs::msg::MarkerArray ma;
210 ma.markers.push_back(marker);
211
212 stateMarkerPublisher_->publish(ma);
213 }

References currentState_, and stateMarkerPublisher_.

◆ run() [1/5]

void LEDActionServer::run ( )
inline

run()

Definition at line 144 of file led_action_server_node.cpp.

145 {
146 RCLCPP_INFO(this->get_logger(), "Creating tool action server");
147 //as_ = std::make_shared<Server>(n, "led_action_server", boost::bind(&LEDActionServer::execute, this, _1), false);
148
149 this->as_ = rclcpp_action::create_server<sm_dance_bot::action::LEDControl>(
150 this, "led_action_server",
151 std::bind(&LEDActionServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),
152 std::bind(&LEDActionServer::handle_cancel, this, std::placeholders::_1),
153 std::bind(&LEDActionServer::handle_accepted, this, std::placeholders::_1));
154
155 RCLCPP_INFO(get_logger(), "Starting Tool Action Server");
157 this->create_publisher<visualization_msgs::msg::MarkerArray>("tool_markers", 1);
158 }
std::shared_ptr< rclcpp_action::Server< sm_dance_bot::action::LEDControl > > as_
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID &, std::shared_ptr< const sm_dance_bot::action::LEDControl::Goal >)
rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr< GoalHandleLEDControl >)
void handle_accepted(const std::shared_ptr< GoalHandleLEDControl > goal_handle)

References handle_accepted(), handle_cancel(), handle_goal(), and stateMarkerPublisher_.

Here is the call graph for this function:

◆ run() [2/5]

void LEDActionServer::run ( )
inline

run()

Definition at line 144 of file led_action_server_node.cpp.

145 {
146 RCLCPP_INFO(this->get_logger(), "Creating tool action server");
147 //as_ = std::make_shared<Server>(n, "led_action_server", boost::bind(&LEDActionServer::execute, this, _1), false);
148
149 this->as_ = rclcpp_action::create_server<sm_dance_bot_strikes_back::action::LEDControl>(
150 this, "led_action_server",
151 std::bind(&LEDActionServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),
152 std::bind(&LEDActionServer::handle_cancel, this, std::placeholders::_1),
153 std::bind(&LEDActionServer::handle_accepted, this, std::placeholders::_1));
154
155 RCLCPP_INFO(get_logger(), "Starting Tool Action Server");
157 this->create_publisher<visualization_msgs::msg::MarkerArray>("tool_markers", 1);
158 }

References handle_accepted(), handle_cancel(), handle_goal(), and stateMarkerPublisher_.

Here is the call graph for this function:

◆ run() [3/5]

void LEDActionServer::run ( )
inline

run()

Definition at line 144 of file led_action_server_node.cpp.

145 {
146 RCLCPP_INFO(this->get_logger(), "Creating tool action server");
147 //as_ = std::make_shared<Server>(n, "led_action_server", boost::bind(&LEDActionServer::execute, this, _1), false);
148
149 this->as_ = rclcpp_action::create_server<sm_dance_bot_warehouse::action::LEDControl>(
150 this, "led_action_server",
151 std::bind(&LEDActionServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),
152 std::bind(&LEDActionServer::handle_cancel, this, std::placeholders::_1),
153 std::bind(&LEDActionServer::handle_accepted, this, std::placeholders::_1));
154
155 RCLCPP_INFO(get_logger(), "Starting Tool Action Server");
157 this->create_publisher<visualization_msgs::msg::MarkerArray>("tool_markers", 1);
158 }

References handle_accepted(), handle_cancel(), handle_goal(), and stateMarkerPublisher_.

Here is the call graph for this function:

◆ run() [4/5]

void LEDActionServer::run ( )
inline

run()

Definition at line 144 of file led_action_server_node.cpp.

145 {
146 RCLCPP_INFO(this->get_logger(), "Creating tool action server");
147 //as_ = std::make_shared<Server>(n, "led_action_server", boost::bind(&LEDActionServer::execute, this, _1), false);
148
149 this->as_ = rclcpp_action::create_server<sm_dance_bot_warehouse_2::action::LEDControl>(
150 this, "led_action_server",
151 std::bind(&LEDActionServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),
152 std::bind(&LEDActionServer::handle_cancel, this, std::placeholders::_1),
153 std::bind(&LEDActionServer::handle_accepted, this, std::placeholders::_1));
154
155 RCLCPP_INFO(get_logger(), "Starting Tool Action Server");
157 this->create_publisher<visualization_msgs::msg::MarkerArray>("tool_markers", 1);
158 }

References handle_accepted(), handle_cancel(), handle_goal(), and stateMarkerPublisher_.

Here is the call graph for this function:

◆ run() [5/5]

void LEDActionServer::run ( )
inline

run()

Definition at line 144 of file led_action_server_node.cpp.

145 {
146 RCLCPP_INFO(this->get_logger(), "Creating tool action server");
147 //as_ = std::make_shared<Server>(n, "led_action_server", boost::bind(&LEDActionServer::execute, this, _1), false);
148
149 this->as_ = rclcpp_action::create_server<sm_dance_bot_warehouse_3::action::LEDControl>(
150 this, "led_action_server",
151 std::bind(&LEDActionServer::handle_goal, this, std::placeholders::_1, std::placeholders::_2),
152 std::bind(&LEDActionServer::handle_cancel, this, std::placeholders::_1),
153 std::bind(&LEDActionServer::handle_accepted, this, std::placeholders::_1));
154
155 RCLCPP_INFO(get_logger(), "Starting Tool Action Server");
157 this->create_publisher<visualization_msgs::msg::MarkerArray>("tool_markers", 1);
158 }

References handle_accepted(), handle_cancel(), handle_goal(), and stateMarkerPublisher_.

Here is the call graph for this function:

Member Data Documentation

◆ as_ [1/5]

std::shared_ptr<rclcpp_action::Server<sm_dance_bot::action::LEDControl> > LEDActionServer::as_

Definition at line 42 of file led_action_server_node.cpp.

◆ as_ [2/5]

std::shared_ptr<rclcpp_action::Server<sm_dance_bot_strikes_back::action::LEDControl> > LEDActionServer::as_

Definition at line 42 of file led_action_server_node.cpp.

◆ as_ [3/5]

std::shared_ptr<rclcpp_action::Server<sm_dance_bot_warehouse::action::LEDControl> > LEDActionServer::as_

Definition at line 42 of file led_action_server_node.cpp.

◆ as_ [4/5]

std::shared_ptr<rclcpp_action::Server<sm_dance_bot_warehouse_2::action::LEDControl> > LEDActionServer::as_

Definition at line 42 of file led_action_server_node.cpp.

◆ as_ [5/5]

std::shared_ptr<rclcpp_action::Server<sm_dance_bot_warehouse_3::action::LEDControl> > LEDActionServer::as_

Definition at line 42 of file led_action_server_node.cpp.

◆ cmd

uint8_t LEDActionServer::cmd

Definition at line 48 of file led_action_server_node.cpp.

Referenced by execute().

◆ currentState_

uint8_t LEDActionServer::currentState_

Definition at line 50 of file led_action_server_node.cpp.

Referenced by execute(), LEDActionServer(), and publishStateMarker().

◆ stateMarkerPublisher_

rclcpp::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr LEDActionServer::stateMarkerPublisher_

Definition at line 46 of file led_action_server_node.cpp.

Referenced by publishStateMarker(), and run().


The documentation for this class was generated from the following files: