1+ // Copyright 2016 Open Source Robotics Foundation, Inc.
2+
3+ // Licensed under the Apache License, Version 2.0 (the "License");
4+ // you may not use this file except in compliance with the License.
5+ // You may obtain a copy of the License at
6+
7+ // http://www.apache.org/licenses/LICENSE-2.0
8+
9+ // Unless required by applicable law or agreed to in writing, software
10+ // distributed under the License is distributed on an "AS IS" BASIS,
11+ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+ // See the License for the specific language governing permissions and
13+ // limitations under the License.
14+
15+ #include < functional>
16+ #include < future>
17+ #include < memory>
18+ #include < sstream>
19+ #include < string>
20+
21+ #include " random_generator/action/randomizer.hpp"
22+
23+ #include " rclcpp/rclcpp.hpp"
24+ #include " rclcpp_action/rclcpp_action.hpp"
25+ #include " rclcpp_components/register_node_macro.hpp"
26+
27+ namespace random_generator {
28+ class RandomizerActionClient : public rclcpp ::Node {
29+ public:
30+ using Randomizer = action::Randomizer;
31+ using GoalHandleRandomizer = rclcpp_action::ClientGoalHandle<Randomizer>;
32+
33+ explicit RandomizerActionClient (const rclcpp::NodeOptions& options)
34+ : Node(" randomizer_action_client" , options) {
35+ this ->client_ptr_ = rclcpp_action::create_client<Randomizer>(this , " randomizer" );
36+
37+ this ->timer_ = this ->create_wall_timer (std::chrono::milliseconds (500 ),
38+ std::bind (&RandomizerActionClient::send_goal, this ));
39+ }
40+
41+ void send_goal () {
42+ using namespace std ::placeholders;
43+
44+ this ->timer_ ->cancel ();
45+
46+ if (!this ->client_ptr_ ->wait_for_action_server ()) {
47+ RCLCPP_ERROR (this ->get_logger (), " Action server not available after waiting" );
48+ rclcpp::shutdown ();
49+ }
50+
51+ auto goal_msg = Randomizer::Goal ();
52+ goal_msg.number_of_values = 10 ;
53+ goal_msg.min_val = 0.5 ;
54+ goal_msg.max_val = 9.5 ;
55+
56+ RCLCPP_INFO (this ->get_logger (), " Sending goal" );
57+
58+ auto send_goal_options = rclcpp_action::Client<Randomizer>::SendGoalOptions ();
59+ send_goal_options.goal_response_callback =
60+ std::bind (&RandomizerActionClient::goal_response_callback, this , _1);
61+ send_goal_options.feedback_callback =
62+ std::bind (&RandomizerActionClient::feedback_callback, this , _1, _2);
63+ send_goal_options.result_callback =
64+ std::bind (&RandomizerActionClient::result_callback, this , _1);
65+ this ->client_ptr_ ->async_send_goal (goal_msg, send_goal_options);
66+ }
67+
68+ private:
69+ rclcpp_action::Client<Randomizer>::SharedPtr client_ptr_;
70+ rclcpp::TimerBase::SharedPtr timer_;
71+
72+ void goal_response_callback (std::shared_future<GoalHandleRandomizer::SharedPtr> future) {
73+ auto goal_handle = future.get ();
74+ if (!goal_handle) {
75+ RCLCPP_ERROR (this ->get_logger (), " Goal was rejected by server" );
76+ } else {
77+ RCLCPP_INFO (this ->get_logger (), " Goal accepted by server, waiting for result" );
78+ }
79+ }
80+
81+ void feedback_callback (GoalHandleRandomizer::SharedPtr,
82+ const std::shared_ptr<const Randomizer::Feedback> feedback) {
83+ std::stringstream ss;
84+ ss << std::setprecision (6 );
85+ ss << " Next random number: " << feedback->new_random_value
86+ << " . \t Done: " << feedback->number_of_random_values_calculated << " values." ;
87+ RCLCPP_INFO (this ->get_logger (), ss.str ().c_str ());
88+ }
89+
90+ void result_callback (const GoalHandleRandomizer::WrappedResult& result_handle) {
91+ switch (result_handle.code ) {
92+ case rclcpp_action::ResultCode::SUCCEEDED:
93+ break ;
94+ case rclcpp_action::ResultCode::ABORTED:
95+ RCLCPP_ERROR (this ->get_logger (), " Goal was aborted" );
96+ return ;
97+ case rclcpp_action::ResultCode::CANCELED:
98+ RCLCPP_ERROR (this ->get_logger (), " Goal was canceled" );
99+ return ;
100+ default :
101+ RCLCPP_ERROR (this ->get_logger (), " Unknown result code" );
102+ return ;
103+ }
104+ std::stringstream ss;
105+ ss << " Result received: " ;
106+ for (auto number : result_handle.result ->random_values ) {
107+ ss << number << " " ;
108+ }
109+ RCLCPP_INFO (this ->get_logger (), ss.str ().c_str ());
110+ rclcpp::shutdown ();
111+ }
112+ }; // class RandomizerActionClient
113+
114+ } // namespace random_generator
115+
116+ RCLCPP_COMPONENTS_REGISTER_NODE (random_generator::RandomizerActionClient)
0 commit comments