ROSAriacKitTrayPlugin.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2012-2016 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 #include <string>
00019 
00020 #include <osrf_gear/KitTray.h>
00021 
00022 #include "ROSAriacKitTrayPlugin.hh"
00023 
00024 using namespace gazebo;
00025 GZ_REGISTER_MODEL_PLUGIN(KitTrayPlugin)
00026 
00027 
00028 KitTrayPlugin::KitTrayPlugin() : SideContactPlugin()
00029 {
00030 }
00031 
00033 KitTrayPlugin::~KitTrayPlugin()
00034 {
00035   event::Events::DisconnectWorldUpdateBegin(this->updateConnection);
00036   this->parentSensor.reset();
00037   this->world.reset();
00038 }
00039 
00041 void KitTrayPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
00042 {
00043 
00044   SideContactPlugin::Load(_model, _sdf);
00045   this->trayID = this->parentLink->GetScopedName();
00046 
00047   // Make sure the ROS node for Gazebo has already been initialized
00048   if (!ros::isInitialized())
00049   {
00050     ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00051       << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00052     return;
00053   }
00054 
00055   this->rosNode = new ros::NodeHandle("");
00056   this->currentKitPub = this->rosNode->advertise<osrf_gear::KitTray>(
00057     "/ariac/trays", 1000);
00058 }
00059 
00061 void KitTrayPlugin::OnUpdate(const common::UpdateInfo &/*_info*/)
00062 {
00063   if (!this->newMsg)
00064   {
00065     return;
00066   }
00067 
00068   auto prevNumberContactingModels = this->contactingModels.size();
00069   this->CalculateContactingModels();
00070   if (prevNumberContactingModels != this->contactingModels.size()) {
00071     gzdbg << this->parentLink->GetScopedName() << ": number of contacting models: " \
00072       << this->contactingModels.size() << "\n";
00073   }
00074   this->ProcessContactingModels();
00075   this->PublishKitMsg();
00076 }
00077 
00079 void KitTrayPlugin::ProcessContactingModels()
00080 {
00081   this->currentKit.objects.clear();
00082   auto trayPose = this->parentLink->GetWorldPose().Ign();
00083   for (auto model : this->contactingModels) {
00084     if (model) {
00085       ariac::KitObject object;
00086 
00087       // Determine the object type
00088       object.type = ariac::DetermineModelType(model->GetName());
00089 
00090       // Determine the pose of the object in the frame of the tray
00091       math::Pose objectPose = model->GetWorldPose();
00092       ignition::math::Matrix4d transMat(trayPose);
00093       ignition::math::Matrix4d objectPoseMat(objectPose.Ign());
00094       object.pose = (transMat.Inverse() * objectPoseMat).Pose();
00095 
00096       this->currentKit.objects.push_back(object);
00097     }
00098   }
00099 }
00100 
00102 void KitTrayPlugin::PublishKitMsg()
00103 {
00104   // Publish current kit
00105   osrf_gear::KitTray kitTrayMsg;
00106   kitTrayMsg.tray.data = this->trayID;
00107   for (const auto &obj : this->currentKit.objects)
00108   {
00109     osrf_gear::KitObject msgObj;
00110     msgObj.type = obj.type;
00111     msgObj.pose.position.x = obj.pose.pos.x;
00112     msgObj.pose.position.y = obj.pose.pos.y;
00113     msgObj.pose.position.z = obj.pose.pos.z;
00114     msgObj.pose.orientation.x = obj.pose.rot.x;
00115     msgObj.pose.orientation.y = obj.pose.rot.y;
00116     msgObj.pose.orientation.z = obj.pose.rot.z;
00117     msgObj.pose.orientation.w = obj.pose.rot.w;
00118 
00119     // Add the object to the kit.
00120     kitTrayMsg.kit.objects.push_back(msgObj);
00121   }
00122   this->currentKitPub.publish(kitTrayMsg);
00123 }


osrf_gear
Author(s):
autogenerated on Mon Sep 5 2016 03:41:33