Gazebo | Ignition | Community
Ask Your Question
0

Changing color of Model in Gazebo via ModelPlugin

asked 2015-06-19 09:22:37 -0500

goch gravatar image

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

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2015-06-19 14:44:45 -0500

hsu gravatar image

updated 2015-06-19 14:46:35 -0500

edit flag offensive delete link more
0

answered 2015-06-19 09:53:49 -0500

nkoenig gravatar image

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.

edit flag offensive delete link more

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/lightcontrol.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/visual8proto.html .

goch gravatar imagegoch ( 2015-06-19 14:31:32 -0500 )edit
Login/Signup to Answer

Question Tools

1 follower

Stats

Asked: 2015-06-19 09:22:37 -0500

Seen: 5,901 times

Last updated: Jun 19 '15