Changing color of Model in Gazebo via ModelPlugin
I'm currently working on an urban city world for Gazebo Simulator on ROS Indigo and have a problem.
I want to create a Model Plugin, that controls Traffic lights. So I created a model where every Lightbulb is a Link.
TrafficLight::trafficlight_light_RED_link
TrafficLight::trafficlight_light_YELLOW_link
TrafficLight::trafficlight_light_GREEN_link
Then I created a ModelPlugin that should Manage the Colour of the lights.
#include <boost/bind.hpp>
#include <gazebo/gazebo.hh>
#include <gazebo/physics/physics.hh>
#include <gazebo/common/common.hh>
#include "ros/ros.h"
#include "std_msgs/String.h"
#include <stdio.h>
namespace gazebo
{
class ModelPush : public ModelPlugin
{
public: void Load(physics::ModelPtr _parent, sdf::ElementPtr /*_sdf*/)
{
std::cout << "******* Loading Trafficlight Plugin **********" << std::endl;
// Store the pointer to the model
this->model = _parent;
// Listen to the update event. This event is broadcast every
// simulation iteration.
this->updateConnection = event::Events::ConnectWorldUpdateBegin(
boost::bind(&ModelPush::OnUpdate, this, _1));
this->link_vector = this->model->GetLinks();
for (int i=0;i<this->link_vector.size();i++){
std::cout << this->link_vector.at(i)->GetScopedName() << std::endl;
}
}
// Called by the world update start event
public: void OnUpdate(const common::UpdateInfo & /*_info*/)
{
// Apply a small linear velocity to the model.
}
// Pointer to the model
private: physics::ModelPtr model;
// vector for Model Links
private: physics::Link_V link_vector;
// Pointer to the update event connection
private: event::ConnectionPtr updateConnection;
};
// Register this plugin with the simulator
GZ_REGISTER_MODEL_PLUGIN(ModelPush)
}
I found a solution to change the colour of an object here
He used a VisualPlugin and therefore got a
gazebo::rendering::VisualPtr
and so he is able to change Ambient and Diffuse Maps of the Visual Object
But I only have a Pointer to a Model Object. Is there a way to change the colour of an Object via ModelPlugin ? Already searched gazebo-API but couldn't find a solution.
Thanks for your Help
Asked by goch on 2015-06-19 09:22:37 UTC
Answers
A model plugin runs on the server, and does not have direct access to the rendering library. You can send a Visual Message from a model plugin to change the color of a model, but you won't have direct access to a Visual pointer.
Alternatively, your model plugin could move links of different color so that only one link is visible at a time. A red link could be hidden inside the traffic light, while a green link is visible. Then swap the two link's locations to change the light to red.
Asked by nkoenig on 2015-06-19 09:53:49 UTC
Comments
I tried to get more information about the Visual Message and found this:https://github.com/robocup-logistics/gazebo-rcll/blob/master/plugins/src/plugins/light-control/light_control.cpp. He constructs a Visual Message but I couldn't find Documentation about msgs::Visual. Just found the message descriptiopn withe the Variables but not the functions http://osrf-distributions.s3.amazonaws.com/gazebo/msg-api/1.9.0/visual_8proto.html .
Asked by goch on 2015-06-19 14:31:32 UTC
here's an example in haptix using the gz topic approach as mentioned by @nkoenig
and here's a related tutorial with a video at the end:
http://gazebosim.org/tutorials?tut=haptix_world_sim_api&branch=haptix_world_sim_api
Asked by hsu on 2015-06-19 14:44:45 UTC
Comments