qb_hand_gazebo_plugin.h
Go to the documentation of this file.
1 /***
2  * Software License Agreement: BSD 3-Clause License
3  *
4  * Copyright (c) 2016-2018, qbrobotics®
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
8  * following conditions are met:
9  *
10  * * Redistributions of source code must retain the above copyright notice, this list of conditions and the
11  * following disclaimer.
12  *
13  * * Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
14  * following disclaimer in the documentation and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote
17  * products derived from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
22  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
23  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
24  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE
25  * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef QB_HAND_GAZEBO_PLUGIN_H
29 #define QB_HAND_GAZEBO_PLUGIN_H
30 
31 // ROS libraries
32 #include <ros/ros.h>
35 
36 // Gazebo libraries
37 #include <gazebo/gazebo.hh>
38 #include <gazebo/physics/physics.hh>
39 
40 // internal libraries
43 
45 class qbHandGazeboPlugin : public gazebo::ModelPlugin {
46 
47  public:
48  qbHandGazeboPlugin() : ModelPlugin() {}
49  ~qbHandGazeboPlugin() override;
50  void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf) override;
51  void Update(const gazebo::common::UpdateInfo &info);
52 
53  private:
54  std::string getURDF(const std::string &param_name);
55  bool parseTransmissionsFromURDF(const std::string &urdf_string);
56 
57  gazebo::event::ConnectionPtr update_connection_;
58  gazebo::physics::ModelPtr parent_model_;
59  sdf::ElementPtr sdf_;
64  std::vector<transmission_interface::TransmissionInfo> transmissions_;
65  std::shared_ptr<gazebo_ros_control::CombinedRobotHWSim> robot_hw_sim_;
66  std::shared_ptr<controller_manager::ControllerManager> controller_manager_;
67  std::string robot_description_;
68  std::string robot_hw_sim_name_;
69 };
70 } // namespace qb_hand_gazebo_plugin
71 
72 #endif // QB_HAND_GAZEBO_PLUGIN_H
qb_hand_gazebo_plugin::qbHandGazeboPlugin::Load
void Load(gazebo::physics::ModelPtr parent, sdf::ElementPtr sdf) override
Definition: qb_hand_gazebo_plugin.cpp:36
qb_hand_gazebo_plugin::qbHandGazeboPlugin::robot_hw_sim_
std::shared_ptr< gazebo_ros_control::CombinedRobotHWSim > robot_hw_sim_
Definition: qb_hand_gazebo_plugin.h:115
qb_hand_gazebo_plugin::qbHandGazeboPlugin::Update
void Update(const gazebo::common::UpdateInfo &info)
Definition: qb_hand_gazebo_plugin.cpp:86
ros.h
combined_robot_hw_sim.h
qb_hand_gazebo_plugin::qbHandGazeboPlugin::model_nh_control_
ros::NodeHandle model_nh_control_
Definition: qb_hand_gazebo_plugin.h:111
transmission_parser.h
controller_manager.h
qb_hand_gazebo_plugin::qbHandGazeboPlugin::update_connection_
gazebo::event::ConnectionPtr update_connection_
Definition: qb_hand_gazebo_plugin.h:107
qb_hand_gazebo_plugin::qbHandGazeboPlugin
Definition: qb_hand_gazebo_plugin.h:70
qb_hand_gazebo_plugin::qbHandGazeboPlugin::sdf_
sdf::ElementPtr sdf_
Definition: qb_hand_gazebo_plugin.h:109
qb_hand_gazebo_plugin::qbHandGazeboPlugin::robot_description_
std::string robot_description_
Definition: qb_hand_gazebo_plugin.h:117
qb_hand_gazebo_plugin::qbHandGazeboPlugin::transmissions_
std::vector< transmission_interface::TransmissionInfo > transmissions_
Definition: qb_hand_gazebo_plugin.h:114
qb_hand_gazebo_plugin::qbHandGazeboPlugin::robot_hw_sim_name_
std::string robot_hw_sim_name_
Definition: qb_hand_gazebo_plugin.h:118
qb_hand_gazebo_plugin::qbHandGazeboPlugin::control_period_
ros::Duration control_period_
Definition: qb_hand_gazebo_plugin.h:112
qb_hand_gazebo_plugin::qbHandGazeboPlugin::getURDF
std::string getURDF(const std::string &param_name)
Definition: qb_hand_gazebo_plugin.cpp:99
qb_hand_gazebo_plugin
Definition: qb_hand_gazebo_plugin.h:44
qb_hand_gazebo_plugin::qbHandGazeboPlugin::parseTransmissionsFromURDF
bool parseTransmissionsFromURDF(const std::string &urdf_string)
Definition: qb_hand_gazebo_plugin.cpp:118
qb_hand_gazebo_plugin::qbHandGazeboPlugin::parent_model_
gazebo::physics::ModelPtr parent_model_
Definition: qb_hand_gazebo_plugin.h:108
ros::Time
qb_hand_gazebo_plugin::qbHandGazeboPlugin::last_sim_time_ros_
ros::Time last_sim_time_ros_
Definition: qb_hand_gazebo_plugin.h:113
qb_hand_gazebo_plugin::qbHandGazeboPlugin::model_nh_
ros::NodeHandle model_nh_
Definition: qb_hand_gazebo_plugin.h:110
qb_hand_gazebo_plugin::qbHandGazeboPlugin::controller_manager_
std::shared_ptr< controller_manager::ControllerManager > controller_manager_
Definition: qb_hand_gazebo_plugin.h:116
qb_hand_gazebo_plugin::qbHandGazeboPlugin::qbHandGazeboPlugin
qbHandGazeboPlugin()
Definition: qb_hand_gazebo_plugin.h:98
qb_hand_gazebo_hardware_interface.h
ros::Duration
qb_hand_gazebo_plugin::qbHandGazeboPlugin::~qbHandGazeboPlugin
~qbHandGazeboPlugin() override
Definition: qb_hand_gazebo_plugin.cpp:32
ros::NodeHandle


qb_hand_gazebo
Author(s): qbrobotics®
autogenerated on Fri Jul 26 2024 02:22:09