hardware_interface.h
Go to the documentation of this file.
1 /*
2  * Copyright 2017, 2018 Simon Rasmussen (refactor)
3  *
4  * Copyright 2015, 2016 Thomas Timm Andersen (original version)
5  *
6  * Licensed under the Apache License, Version 2.0 (the "License");
7  * you may not use this file except in compliance with the License.
8  * You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS,
14  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15  * See the License for the specific language governing permissions and
16  * limitations under the License.
17  */
18 
19 #pragma once
24 #include <algorithm>
28 
30 {
31 public:
32  virtual bool write() = 0;
33  virtual void start()
34  {
35  }
36  virtual void stop()
37  {
38  }
39  virtual void reset()
40  {
41  }
42 };
43 
45 
47 {
48 private:
49  std::array<double, 6> velocities_, positions_, efforts_;
50 
51 public:
52  JointInterface(std::vector<std::string> &joint_names);
53  void update(RTShared &packet);
54 
56  static const std::string INTERFACE_NAME;
57 };
58 
60 {
61  std::array<double, 6> tcp_;
62 
63 public:
64  WrenchInterface(std::string wrench_frame);
65  void update(RTShared &packet);
67  static const std::string INTERFACE_NAME;
68 };
69 
71 {
72 private:
74  std::array<double, 6> velocity_cmd_, prev_velocity_cmd_;
76 
77 public:
79  std::vector<std::string> &joint_names, double max_vel_change);
80  virtual bool write();
81  virtual void reset();
83  static const std::string INTERFACE_NAME;
84 };
85 
87 {
88 private:
90  std::array<double, 6> position_cmd_;
91 
92 public:
94  std::vector<std::string> &joint_names);
95  virtual bool write();
96  virtual void start();
97  virtual void stop();
98 
100  static const std::string INTERFACE_NAME;
101 };
std::array< double, 6 > velocity_cmd_
static const std::string INTERFACE_NAME
static const std::string INTERFACE_NAME
virtual void reset()
virtual void stop()
hardware_interface::JointStateInterface parent_type
TrajectoryFollower & follower_
static const std::string INTERFACE_NAME
hardware_interface::ForceTorqueSensorInterface parent_type
URCommander & commander_
std::array< double, 6 > position_cmd_
static const std::string INTERFACE_NAME
void update(controller_manager::ControllerManager &cm, const ros::TimerEvent &e)
hardware_interface::PositionJointInterface parent_type
virtual void start()
std::array< double, 6 > tcp_
std::array< double, 6 > velocities_
virtual bool write()=0
hardware_interface::VelocityJointInterface parent_type


ur_modern_driver
Author(s): Thomas Timm Andersen, Simon Rasmussen
autogenerated on Fri Jun 26 2020 03:37:00