cartesian_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_H
19 #define COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_H
20 
21 #include <vector>
22 #include <string>
23 #include <boost/shared_ptr.hpp>
24 
25 #include <ros/ros.h>
26 #include <tf/transform_listener.h>
28 #include <tf/transform_datatypes.h>
29 
31 #include <cob_cartesian_controller/CartesianControllerAction.h>
32 
36 
38 
39 #define DEFAULT_CARTESIAN_TARGET "cartesian_target"
40 
42 {
43 public:
44  bool initialize();
45 
46  // Main functions
47  bool posePathBroadcaster(const geometry_msgs::PoseArray& cartesian_path);
48 
49  // Helper function
50  bool startTracking();
51  bool stopTracking();
52 
54  void goalCallback();
55  void preemptCallback();
56  void actionSuccess(const bool success, const std::string& message);
57  void actionPreempt(const bool success, const std::string& message);
58  void actionAbort(const bool success, const std::string& message);
59 
61  cob_cartesian_controller::MoveLinStruct convertMoveLin(const cob_cartesian_controller::MoveLin& move_lin_msg);
62  cob_cartesian_controller::MoveCircStruct convertMoveCirc(const cob_cartesian_controller::MoveCirc& move_circ_msg);
63 
64 private:
68 
71  bool tracking_;
72 
73  double update_rate_;
75 
77  std::string action_name_;
79  cob_cartesian_controller::CartesianControllerFeedback action_feedback_;
80  cob_cartesian_controller::CartesianControllerResult action_result_;
81 
84 };
85 
86 #endif // COB_CARTESIAN_CONTROLLER_CARTESIAN_CONTROLLER_H
boost::shared_ptr< TrajectoryInterpolator > trajectory_interpolator_
ros::ServiceClient start_tracking_
std::string action_name_
Action interface.
cob_cartesian_controller::CartesianActionStruct acceptGoal(boost::shared_ptr< const cob_cartesian_controller::CartesianControllerGoal > goal)
actionlib::SimpleActionServer< cob_cartesian_controller::CartesianControllerAction > SAS_CartesianControllerAction_t
void actionPreempt(const bool success, const std::string &message)
cob_cartesian_controller::MoveLinStruct convertMoveLin(const cob_cartesian_controller::MoveLin &move_lin_msg)
CartesianControllerUtils utils_
tf::TransformBroadcaster tf_broadcaster_
cob_cartesian_controller::CartesianControllerFeedback action_feedback_
bool posePathBroadcaster(const geometry_msgs::PoseArray &cartesian_path)
ros::ServiceClient stop_tracking_
boost::shared_ptr< SAS_CartesianControllerAction_t > as_
void goalCallback()
Action interface.
cob_cartesian_controller::CartesianControllerResult action_result_
tf::TransformListener tf_listener_
cob_cartesian_controller::MoveCircStruct convertMoveCirc(const cob_cartesian_controller::MoveCirc &move_circ_msg)
void actionSuccess(const bool success, const std::string &message)
void actionAbort(const bool success, const std::string &message)


cob_cartesian_controller
Author(s): Christoph Mark
autogenerated on Thu Apr 8 2021 02:40:13