my_robot_hw_3.h
Go to the documentation of this file.
1 // Copyright (C) 2015, Shadow Robot Company Ltd.
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 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of hiDOF, Inc. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
28 #pragma once
29 
30 
34 
36 {
37 
39 {
40 public:
41  bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh) override;
42  void read(const ros::Time& time, const ros::Duration& period) override;
43  void write(const ros::Time& time, const ros::Duration& period) override;
44 
45 protected:
46 
47 private:
51 
52  std::vector<double> joint_effort_command_;
53  std::vector<double> joint_velocity_command_;
54  std::vector<double> joint_position_;
55  std::vector<double> joint_velocity_;
56  std::vector<double> joint_effort_;
57  std::vector<std::string> joint_name_;
58 };
59 }
std::vector< double > joint_velocity_
Definition: my_robot_hw_3.h:55
bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) override
std::vector< std::string > joint_name_
Definition: my_robot_hw_3.h:57
std::vector< double > joint_position_
Definition: my_robot_hw_3.h:54
hardware_interface::EffortJointInterface ej_interface_
Definition: my_robot_hw_3.h:49
std::vector< double > joint_effort_
Definition: my_robot_hw_3.h:56
std::vector< double > joint_velocity_command_
Definition: my_robot_hw_3.h:53
void write(const ros::Time &time, const ros::Duration &period) override
void read(const ros::Time &time, const ros::Duration &period) override
hardware_interface::VelocityJointInterface vj_interface_
Definition: my_robot_hw_3.h:50
hardware_interface::JointStateInterface js_interface_
Definition: my_robot_hw_3.h:48
std::vector< double > joint_effort_command_
Definition: my_robot_hw_3.h:52


combined_robot_hw_tests
Author(s): Toni Oliver
autogenerated on Mon Feb 28 2022 23:30:21