seed_r7_robot_hardware.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Yohei Kakiuchi (JSK lab.)
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Open Source Robotics Foundation
18  * nor the names of its contributors may be
19  * used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef _ROBOT_HW_H_
37 #define _ROBOT_HW_H_
38 
39 // ros_control
40 #include <control_toolbox/pid.h>
47 
48 // ROS
49 #include <ros/ros.h>
50 #include <std_msgs/Float32.h>
51 #include <pluginlib/class_loader.h>
52 
53 // URDF
54 #include <urdf/model.h>
55 
56 // AERO
60 #include "seed_r7_ros_controller/ResetRobotStatus.h"
61 
62 #include <mutex>
63 
64 //for robot status view
65 #include <std_msgs/String.h>
66 #include <diagnostic_updater/diagnostic_updater.h>
67 
68 namespace robot_hardware
69 {
70 
72 {
73 public:
74  RobotHW() : converter_loader_("seed_r7_ros_controller", "StrokeConverter") { }
75 
76  virtual ~RobotHW() {}
77 
78  virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle &robot_hw_nh);
79  virtual void read(const ros::Time& time, const ros::Duration& period);
80  virtual void write(const ros::Time& time, const ros::Duration& period);
81 
82  void readPos(const ros::Time& time, const ros::Duration& period, bool update);
83  void writeWheel(const std::vector< std::string> &_names,
84  const std::vector<int16_t> &_vel, double _tm_sec);
85  double getPeriod() { return ((double)CONTROL_PERIOD_US_) / (1000 * 1000); }
86 
87  //--specific functions--
88  void runHandScript(uint8_t _number, uint16_t _script, uint8_t _current);
89  void turnWheel(std::vector<int16_t> &_vel);
90  void onWheelServo(bool _value);
91  void getBatteryVoltage(const ros::TimerEvent& _event);
92  void runLedScript(uint8_t _number, uint16_t _script);
93  void setRobotStatus();
94  void setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper& stat);
95  //----------------------
96 
97  bool comm_err_;
98  struct RobotStatus {
102  bool temp_err_;
103  bool res_err_;
107  } robot_status_;
108 
109 private:
111  bool resetRobotStatusCallback(seed_r7_ros_controller::ResetRobotStatus::Request& _req, seed_r7_ros_controller::ResetRobotStatus::Response& _res);
112 
113 protected:
114  // Methods used to control a joint.
117 
118  unsigned int number_of_angles_;
119 
122 
124 
125  std::vector<std::string> joint_list_;
126  std::vector<double> joint_effort_limits_;
127  std::vector<JointType> joint_types_;
128  std::vector<ControlMethod> joint_control_methods_;
129  std::vector<double> joint_position_;
130  std::vector<double> joint_velocity_;
131  std::vector<double> joint_effort_;
132  std::vector<double> joint_position_command_;
133  std::vector<double> joint_velocity_command_;
134  std::vector<double> joint_effort_command_;
135 
136 
137  std::vector<double> prev_ref_strokes_;
138  std::vector<int16_t> upper_act_strokes_;
139  std::vector<int16_t> lower_act_strokes_;
140 
143 
146 
150 
151  std::mutex mutex_lower_;
152  std::mutex mutex_upper_;
153 
154  std::vector<std::string> joint_names_upper_;
155  std::vector<std::string> joint_names_lower_;
156  std::string robot_model_plugin_;
157 
160 
163 
164  //for robot status view
165  diagnostic_updater::Updater diagnostic_updater_;
166 };
167 
168 }
169 
170 #endif
void writeWheel(const std::vector< std::string > &_names, const std::vector< int16_t > &_vel, double _tm_sec)
void turnWheel(std::vector< int16_t > &_vel)
hardware_interface::JointStateInterface js_interface_
void runLedScript(uint8_t _number, uint16_t _script)
std::vector< double > joint_effort_limits_
bool resetRobotStatusCallback(seed_r7_ros_controller::ResetRobotStatus::Request &_req, seed_r7_ros_controller::ResetRobotStatus::Response &_res)
void setDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
boost::shared_ptr< seed_converter::StrokeConverter > stroke_converter_
joint_limits_interface::PositionJointSaturationInterface pj_sat_interface_
boost::shared_ptr< robot_hardware::UpperController > controller_upper_
struct robot_hardware::RobotHW::RobotStatus robot_status_
std::vector< std::string > joint_names_upper_
std::vector< std::string > joint_names_lower_
boost::shared_ptr< robot_hardware::LowerController > controller_lower_
std::vector< double > joint_position_
pluginlib::ClassLoader< seed_converter::StrokeConverter > converter_loader_
std::vector< double > prev_ref_strokes_
std::vector< double > joint_effort_
std::vector< double > joint_position_command_
std::vector< double > joint_effort_command_
void getBatteryVoltage(const ros::TimerEvent &_event)
hardware_interface::PositionJointInterface pj_interface_
std::vector< JointType > joint_types_
std::vector< ControlMethod > joint_control_methods_
std::vector< int16_t > lower_act_strokes_
void readPos(const ros::Time &time, const ros::Duration &period, bool update)
std::vector< int16_t > upper_act_strokes_
void update(controller_manager::ControllerManager &cm, const ros::TimerEvent &e)
ros::ServiceServer reset_robot_status_server_
diagnostic_updater::Updater diagnostic_updater_
std::vector< double > joint_velocity_
std::vector< std::string > joint_list_
std::vector< double > joint_velocity_command_
virtual void read(const ros::Time &time, const ros::Duration &period)
void runHandScript(uint8_t _number, uint16_t _script, uint8_t _current)
virtual void write(const ros::Time &time, const ros::Duration &period)
virtual bool init(ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh)


seed_r7_ros_controller
Author(s): Yohei Kakiuchi
autogenerated on Sun Apr 18 2021 02:40:34