Skip to content
Snippets Groups Projects
Commit 83768d25 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Use only topic to set material

parent 67daaca3
No related branches found
No related tags found
1 merge request!1Update doc/images/sample_box_red.png, doc/images/sample_box_green.png,...
...@@ -50,20 +50,21 @@ ...@@ -50,20 +50,21 @@
ros::Subscriber material_subscriber; ros::Subscriber material_subscriber;
void materialCallback(const std_msgs::String::ConstPtr& msg); void materialCallback(const std_msgs::String::ConstPtr& msg);
bool new_material; bool new_material;
ros::Subscriber color_subscriber;
void colorCallback(const std_msgs::ColorRGBA::ConstPtr& msg); //ros::Subscriber color_subscriber;
bool new_color; //void colorCallback(const std_msgs::ColorRGBA::ConstPtr& msg);
//bool new_color;
ros::ServiceServer trigger_server;
bool triggerCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res); //ros::ServiceServer trigger_server;
//bool triggerCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
std::string plugin_name; std::string plugin_name;
std::string element_name; std::string element_name;
std::string material_name; std::string material_name;
std::string material1_name; std::string material1_name;
std::string material2_name; std::string material2_name;
bool trigger_state; //bool trigger_state;
ignition::math::Color color; //ignition::math::Color color;
}; };
//} //}
......
...@@ -27,10 +27,10 @@ ColorPlugin::ColorPlugin() ...@@ -27,10 +27,10 @@ ColorPlugin::ColorPlugin()
this->material1_name="Gazebo/Red"; this->material1_name="Gazebo/Red";
this->material2_name="Gazebo/Green"; this->material2_name="Gazebo/Green";
this->plugin_name="empty_plugin_name"; this->plugin_name="empty_plugin_name";
this->color.Set(1, 0 , 0); //this->color.Set(1, 0 , 0);
this->new_material=false; this->new_material=false;
this->new_color=false; //this->new_color=false;
this->trigger_state=false; //this->trigger_state=false;
} }
...@@ -45,6 +45,8 @@ void ColorPlugin::Load(gazebo::rendering::VisualPtr _parent, sdf::ElementPtr _sd ...@@ -45,6 +45,8 @@ void ColorPlugin::Load(gazebo::rendering::VisualPtr _parent, sdf::ElementPtr _sd
this->plugin_name = this->GetHandle().c_str(); this->plugin_name = this->GetHandle().c_str();
ROS_INFO("handle=%s", this->GetHandle().c_str());
if(_sdf->HasElement("material")) if(_sdf->HasElement("material"))
{ {
this->material1_name = _sdf->GetElement("material")->Get<std::string>(); this->material1_name = _sdf->GetElement("material")->Get<std::string>();
...@@ -74,43 +76,47 @@ void ColorPlugin::threadFunction() ...@@ -74,43 +76,47 @@ void ColorPlugin::threadFunction()
{ {
this->nh = new ros::NodeHandle("~"); this->nh = new ros::NodeHandle("~");
std::string material_topic = "/" + this->plugin_name + "/" + "set_material"; std::string material_topic = "/" + this->plugin_name + "/" + "set_material";
std::string color_topic = "/" + this->plugin_name + "/" + "set_color"; //std::string color_topic = "/" + this->plugin_name + "/" + "set_color";
std::string srv_topic = "/" + this->plugin_name + "/" + "trigger"; //std::string srv_topic = "/" + this->plugin_name + "/" + "trigger";
this->material_subscriber = this->nh->subscribe<std_msgs::String>(material_topic, 1, boost::bind(&ColorPlugin::materialCallback, this, _1)); this->material_subscriber = this->nh->subscribe<std_msgs::String>(material_topic, 1, boost::bind(&ColorPlugin::materialCallback, this, _1));
this->color_subscriber = this->nh->subscribe<std_msgs::ColorRGBA>(color_topic, 1, boost::bind(&ColorPlugin::colorCallback, this, _1)); //this->color_subscriber = this->nh->subscribe<std_msgs::ColorRGBA>(color_topic, 1, boost::bind(&ColorPlugin::colorCallback, this, _1));
this->trigger_server = this->nh->advertiseService(srv_topic, &ColorPlugin::triggerCallback, this); //this->trigger_server = this->nh->advertiseService(srv_topic, &ColorPlugin::triggerCallback, this);
} }
} }
void ColorPlugin::materialCallback(const std_msgs::String::ConstPtr& _msg) void ColorPlugin::materialCallback(const std_msgs::String::ConstPtr& _msg)
{ {
std_msgs::String name_msg = *_msg; std_msgs::String name_msg = *_msg;
if(!this->trigger_state) if(name_msg.data.size()==0)
this->material1_name=name_msg.data; {
if(this->material_name==this->material1_name)
this->material_name=this->material2_name;
else if(this->material_name==this->material2_name)
this->material_name=this->material1_name;
}
else else
this->material2_name=name_msg.data; this->material_name = name_msg.data;
this->material_name = name_msg.data;
this->new_material=true; this->new_material=true;
} }
void ColorPlugin::colorCallback(const std_msgs::ColorRGBA::ConstPtr& _msg) // void ColorPlugin::colorCallback(const std_msgs::ColorRGBA::ConstPtr& _msg)
{ // {
this->color.Set(_msg->r, _msg->g, _msg->b); // this->color.Set(_msg->r, _msg->g, _msg->b);
this->new_color=true; // this->new_color=true;
} // }
bool ColorPlugin::triggerCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) // bool ColorPlugin::triggerCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
{ // {
if(!this->trigger_state) // if(!this->trigger_state)
this->material_name=this->material2_name; // this->material_name=this->material2_name;
else // else
this->material_name=this->material1_name; // this->material_name=this->material1_name;
this->trigger_state = !this->trigger_state; // this->trigger_state = !this->trigger_state;
this->new_material=true; // this->new_material=true;
return true; // return true;
} // }
void ColorPlugin::OnUpdate() void ColorPlugin::OnUpdate()
{ {
...@@ -119,11 +125,11 @@ void ColorPlugin::OnUpdate() ...@@ -119,11 +125,11 @@ void ColorPlugin::OnUpdate()
this->model->SetMaterial(this->material_name); this->model->SetMaterial(this->material_name);
this->new_material=false; this->new_material=false;
} }
else if(this->new_color) // else if(this->new_color)
{ // {
this->model->SetAmbient(this->color); // this->model->SetAmbient(this->color);
this->model->SetDiffuse(this->color); // this->model->SetDiffuse(this->color);
this->model->SetEmissive(this->color); // this->model->SetEmissive(this->color);
this->new_color=false; // this->new_color=false;
} // }
} }
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment