quadrotor_interface.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012-2016, Institute of Flight Systems and Automatic Control,
3 // Technische Universität Darmstadt.
4 // All rights reserved.
5 
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of hector_quadrotor nor the names of its contributors
14 // may be used to endorse or promote products derived from this software
15 // without specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef HECTOR_QUADROTOR_INTERFACE_QUADROTOR_INTERFACE_H
30 #define HECTOR_QUADROTOR_INTERFACE_QUADROTOR_INTERFACE_H
31 
33 
35 
36 #include <map>
37 #include <list>
38 
40 {
41 
43 {
44 public:
46 
47  virtual ~QuadrotorInterface();
48 
49  // TODO template
50  void registerPose(geometry_msgs::Pose *pose){
51  pose_ = PoseHandlePtr(new PoseHandle(this, pose));
52  }
53 
54  void registerTwist(geometry_msgs::Twist *twist){
55  twist_ = TwistHandlePtr(new TwistHandle(this, twist));
56  }
57 
58  void registerAccel(geometry_msgs::Accel *accel){
60  }
61  void registerSensorImu(sensor_msgs::Imu *imu){
62  imu_ = ImuHandlePtr(new ImuHandle(this, imu));
63  }
64 
65  void registerMotorStatus(hector_uav_msgs::MotorStatus *motor_status){
66  motor_status_ = MotorStatusHandlePtr(new MotorStatusHandle(this, motor_status));
67  }
68 
70  {
71  return pose_;
72  }
73 
75  {
76  return twist_;
77  }
78 
80  {
81  return accel_;
82  }
83 
85  {
86  return imu_;
87  }
88 
90  {
91  return motor_status_;
92  }
93 
99 
100  template<typename HandleType>
102  {
103  return boost::shared_ptr<HandleType>(new HandleType(this));
104  }
105 
106  template<typename HandleType>
107  boost::shared_ptr<HandleType> addInput(const std::string &name)
108  {
109  boost::shared_ptr<HandleType> input = getInput<HandleType>(name);
110  if (input) { return input; }
111 
112  // create new input handle
113  input.reset(new HandleType(this, name));
114  inputs_[name] = input;
115 
116  // connect to outputs of same name
117  if (outputs_.count(name))
118  {
119  boost::shared_ptr<HandleType> output = boost::dynamic_pointer_cast<HandleType>(outputs_.at(name));
120  if (output) output->connectTo(*input);
121  }
122 
123  return input;
124  }
125 
126  template<typename HandleType>
127  boost::shared_ptr<HandleType> addOutput(const std::string &name)
128  {
129  boost::shared_ptr<HandleType> output = getOutput<HandleType>(name);
130  if (output) { return output; }
131 
132  // create new output handle
133  output.reset(new HandleType(this, name));
134  outputs_[name] = output;
135  *output = output->ownData(new typename HandleType::ValueType());
136 
137  //claim resource
138  claim(name);
139 
140  // connect to inputs of same name
141  if (inputs_.count(name))
142  {
143  boost::shared_ptr<HandleType> input = boost::dynamic_pointer_cast<HandleType>(inputs_.at(name));
144  if (input) output->connectTo(*input);
145  }
146 
147  return output;
148  }
149 
150  template<typename HandleType>
151  boost::shared_ptr<HandleType> getOutput(const std::string &name) const
152  {
153  if (!outputs_.count(name)) { return boost::shared_ptr<HandleType>(); }
154  return boost::dynamic_pointer_cast<HandleType>(outputs_.at(name));
155  }
156 
157  template<typename HandleType>
158  boost::shared_ptr<HandleType> getInput(const std::string &name) const
159  {
160  if (!inputs_.count(name)) { return boost::shared_ptr<HandleType>(); }
161  return boost::dynamic_pointer_cast<HandleType>(inputs_.at(name));
162  }
163 
164  template<typename HandleType>
165  typename HandleType::ValueType const *getCommand(const std::string &name) const
166  {
167  boost::shared_ptr<HandleType> output = getOutput<HandleType>(name);
168  if (!output || !output->connected())
169  { return 0; }
170  return &(output->command());
171  }
172 
173  const Pose *getPoseCommand() const;
174  const Twist *getTwistCommand() const;
175  const Wrench *getWrenchCommand() const;
176  const MotorCommand *getMotorCommand() const;
177 
178  bool enabled(const CommandHandle *handle) const;
179  bool start(const CommandHandle *handle);
180  bool stop(const CommandHandle *handle);
181  void disconnect(const CommandHandle *handle);
182 
183  bool preempt(const CommandHandle *handle);
184 
185 private:
186  std::map<std::string, CommandHandlePtr> inputs_;
187  std::map<std::string, CommandHandlePtr> outputs_;
188  std::map<std::string, const CommandHandle *> enabled_;
189 };
190 
191 } // namespace hector_quadrotor_interface
192 
193 #endif // HECTOR_QUADROTOR_INTERFACE_QUADROTOR_INTERFACE_H
boost::shared_ptr< TwistHandle > TwistHandlePtr
Definition: handles.h:121
boost::shared_ptr< HandleType > getOutput(const std::string &name) const
void registerPose(geometry_msgs::Pose *pose)
boost::shared_ptr< ImuHandle > ImuHandlePtr
Definition: handles.h:159
void registerMotorStatus(hector_uav_msgs::MotorStatus *motor_status)
boost::shared_ptr< HandleType > addInput(const std::string &name)
boost::shared_ptr< AccelerationHandle > AccelerationHandlePtr
Definition: handles.h:135
void disconnect(const CommandHandle *handle)
boost::shared_ptr< HandleType > getInput(const std::string &name) const
virtual void claim(std::string resource)
std::map< std::string, CommandHandlePtr > outputs_
HandleType::ValueType const * getCommand(const std::string &name) const
boost::shared_ptr< HandleType > addOutput(const std::string &name)
boost::shared_ptr< HandleType > getHandle()
bool enabled(const CommandHandle *handle) const
void registerTwist(geometry_msgs::Twist *twist)
std::map< std::string, const CommandHandle * > enabled_
void registerAccel(geometry_msgs::Accel *accel)
boost::shared_ptr< MotorStatusHandle > MotorStatusHandlePtr
Definition: handles.h:172
boost::shared_ptr< PoseHandle > PoseHandlePtr
Definition: handles.h:107
std::map< std::string, CommandHandlePtr > inputs_


hector_quadrotor_interface
Author(s): Johannes Meyer , Paul Bovbel
autogenerated on Mon Jun 10 2019 13:36:46