Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #ifndef _GAZEBO_KIT_TRAY_PLUGIN_HH_
00022 #define _GAZEBO_KIT_TRAY_PLUGIN_HH_
00023
00024 #include <string>
00025
00026 #include <ros/ros.h>
00027
00028 #include <gazebo/common/Plugin.hh>
00029 #include <gazebo/msgs/msgs.hh>
00030 #include <gazebo/sensors/sensors.hh>
00031 #include <gazebo/util/system.hh>
00032 #include <osrf_gear/ARIAC.hh>
00033 #include "SideContactPlugin.hh"
00034
00035 namespace gazebo
00036 {
00038 class GAZEBO_VISIBLE KitTrayPlugin : public SideContactPlugin
00039 {
00041 public: KitTrayPlugin();
00042
00044 public: virtual ~KitTrayPlugin();
00045
00049 public: virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
00050
00052 protected: void OnUpdate(const common::UpdateInfo &_info);
00053
00055 protected: void ProcessContactingModels();
00056
00058 public: std::string DetermineModelType(const std::string &modelName);
00059
00061 protected: void PublishKitMsg();
00062
00064 protected: ariac::Kit currentKit;
00065
00067 protected: std::string trayID;
00068
00070 protected: ros::NodeHandle *rosNode;
00071
00073 protected: ros::Publisher currentKitPub;
00074 };
00075 }
00076 #endif
00077