cartesian_joint_converter.h
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
30 #ifndef XPP_VIS_CARTESIAN_JOINT_CONVERTER_H_
31 #define XPP_VIS_CARTESIAN_JOINT_CONVERTER_H_
32 
33 #include <string>
34 
35 #include <ros/publisher.h>
36 #include <ros/subscriber.h>
37 
38 #include <xpp_msgs/RobotStateCartesian.h>
39 
40 #include "inverse_kinematics.h"
41 
42 namespace xpp {
43 
52 public:
60  const std::string& cart_topic,
61  const std::string& joint_topic);
62  virtual ~CartesianJointConverter () = default;
63 
64 private:
65  void StateCallback(const xpp_msgs::RobotStateCartesian& msg);
66 
69 
71 };
72 
73 } /* namespace xpp */
74 
75 #endif /* XPP_VIS_CARTESIAN_JOINT_CONVERTER_H_ */
std::shared_ptr< InverseKinematics > Ptr
InverseKinematics::Ptr inverse_kinematics_
virtual ~CartesianJointConverter()=default
Converts a Cartesian robot representation to joint angles.
void StateCallback(const xpp_msgs::RobotStateCartesian &msg)
CartesianJointConverter(const InverseKinematics::Ptr &ik, const std::string &cart_topic, const std::string &joint_topic)
Creates a converter initializing the subscriber and publisher.


xpp_vis
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 7 2019 02:34:51