gazebo_ros_color.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef VMRC_GAZEBO_GAZEBO_ROS_COLOR_HH_
19 #define VMRC_GAZEBO_GAZEBO_ROS_COLOR_HH_
20 
21 #include <ros/ros.h>
22 #include <std_msgs/ColorRGBA.h>
23 #include <gazebo/common/Plugin.hh>
24 #include <gazebo/rendering/Visual.hh>
25 #include <sdf/sdf.hh>
26 
37 class GazeboRosColor : public gazebo::VisualPlugin
38 {
39  // Documentation inherited.
40  public: void Load(gazebo::rendering::VisualPtr _parent,
41  sdf::ElementPtr _sdf);
42 
44  private: gazebo::rendering::VisualPtr visual = nullptr;
45 
48 
51 
54  void ColorCallback(const std_msgs::ColorRGBAConstPtr &_msg);
55 };
56 
57 #endif
ros::Subscriber colorSub
Subscriber to accept color change requests.
void ColorCallback(const std_msgs::ColorRGBAConstPtr &_msg)
gazebo::rendering::VisualPtr visual
Pointer to the visual element to modify.
Visual plugin for changing the color of some visual elements using ROS messages. This plugin accepts ...
void Load(gazebo::rendering::VisualPtr _parent, sdf::ElementPtr _sdf)
ros::NodeHandle nh
ROS Node handle.


vmrc_gazebo
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Sun Feb 17 2019 03:14:16