Skip to content

Commit

Permalink
Factor out marker creation from ROS msg into new createMarker() (#1183)
Browse files Browse the repository at this point in the history
* factor out createMarker() function

* [style] use scope block, even on single-body if statements

* [style] use scope block, even on single-body if statements

* [style] use scope block, even on single-body if statements

* [style] inconsistent parenthesis padding

on both sides or neither is fine, asymmetric makes me itch :)
  • Loading branch information
rhaschke authored and dhood committed Feb 23, 2018
1 parent fe0512e commit 772da5f
Show file tree
Hide file tree
Showing 5 changed files with 142 additions and 123 deletions.
1 change: 1 addition & 0 deletions src/rviz/default_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ set(SOURCE_FILES
map_display.cpp
marker_array_display.cpp
marker_display.cpp
marker_utils.cpp
markers/arrow_marker.cpp
markers/line_list_marker.cpp
markers/line_strip_marker.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,15 +48,8 @@

#include "rviz/ogre_helpers/line.h"

#include "rviz/default_plugin/markers/shape_marker.h"
#include "rviz/default_plugin/markers/arrow_marker.h"
#include "rviz/default_plugin/markers/line_list_marker.h"
#include "rviz/default_plugin/markers/line_strip_marker.h"
#include "rviz/default_plugin/marker_utils.h"
#include "rviz/default_plugin/markers/points_marker.h"
#include "rviz/default_plugin/markers/text_view_facing_marker.h"
#include "rviz/default_plugin/markers/mesh_resource_marker.h"
#include "rviz/default_plugin/markers/triangle_list_marker.h"
#include "rviz/default_plugin/markers/marker_base.h"

#include "rviz/default_plugin/interactive_markers/interactive_marker_control.h"
#include "rviz/default_plugin/interactive_markers/interactive_marker.h"
Expand Down Expand Up @@ -94,64 +87,15 @@ void InteractiveMarkerControl::makeMarkers( const visualization_msgs::Interactiv
{
for (unsigned i = 0; i < message.markers.size(); i++)
{
MarkerBasePtr marker;

// create a marker with the given type
switch (message.markers[i].type)
{
case visualization_msgs::Marker::CUBE:
case visualization_msgs::Marker::CYLINDER:
case visualization_msgs::Marker::SPHERE:
{
marker.reset(new ShapeMarker(0, context_, markers_node_));
}
break;

case visualization_msgs::Marker::ARROW:
{
marker.reset(new ArrowMarker(0, context_, markers_node_));
}
break;

case visualization_msgs::Marker::LINE_STRIP:
{
marker.reset(new LineStripMarker(0, context_, markers_node_));
}
break;
case visualization_msgs::Marker::LINE_LIST:
{
marker.reset(new LineListMarker(0, context_, markers_node_));
}
break;
case visualization_msgs::Marker::SPHERE_LIST:
case visualization_msgs::Marker::CUBE_LIST:
case visualization_msgs::Marker::POINTS:
{
PointsMarkerPtr points_marker;
points_marker.reset(new PointsMarker(0, context_, markers_node_));
points_markers_.push_back( points_marker );
marker = points_marker;
}
break;
case visualization_msgs::Marker::TEXT_VIEW_FACING:
{
marker.reset(new TextViewFacingMarker(0, context_, markers_node_));
}
break;
case visualization_msgs::Marker::MESH_RESOURCE:
{
marker.reset(new MeshResourceMarker(0, context_, markers_node_));
}
break;
MarkerBasePtr marker(createMarker(message.markers[i].type, 0, context_, markers_node_));
if (!marker) {
ROS_ERROR( "Unknown marker type: %d", message.markers[i].type );
}

case visualization_msgs::Marker::TRIANGLE_LIST:
{
marker.reset(new TriangleListMarker(0, context_, markers_node_));
}
break;
default:
ROS_ERROR( "Unknown marker type: %d", message.markers[i].type );
break;
PointsMarkerPtr points_marker = boost::dynamic_pointer_cast<PointsMarker>(marker);
if (points_marker) {
points_markers_.push_back( points_marker );
}

visualization_msgs::MarkerPtr marker_msg( new visualization_msgs::Marker(message.markers[ i ]) );
Expand Down
63 changes: 4 additions & 59 deletions src/rviz/default_plugin/marker_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,14 +31,8 @@

#include <tf/transform_listener.h>

#include "rviz/default_plugin/markers/arrow_marker.h"
#include "rviz/default_plugin/markers/line_list_marker.h"
#include "rviz/default_plugin/markers/line_strip_marker.h"
#include "rviz/default_plugin/markers/mesh_resource_marker.h"
#include "rviz/default_plugin/markers/points_marker.h"
#include "rviz/default_plugin/markers/shape_marker.h"
#include "rviz/default_plugin/markers/text_view_facing_marker.h"
#include "rviz/default_plugin/markers/triangle_list_marker.h"
#include "rviz/default_plugin/markers/marker_base.h"
#include "rviz/default_plugin/marker_utils.h"
#include "rviz/display_context.h"
#include "rviz/frame_manager.h"
#include "rviz/ogre_helpers/arrow.h"
Expand Down Expand Up @@ -373,59 +367,10 @@ void MarkerDisplay::processAdd( const visualization_msgs::Marker::ConstPtr& mess

if ( create )
{
switch ( message->type )
{
case visualization_msgs::Marker::CUBE:
case visualization_msgs::Marker::CYLINDER:
case visualization_msgs::Marker::SPHERE:
{
marker.reset(new ShapeMarker(this, context_, scene_node_));
}
break;

case visualization_msgs::Marker::ARROW:
{
marker.reset(new ArrowMarker(this, context_, scene_node_));
}
break;

case visualization_msgs::Marker::LINE_STRIP:
{
marker.reset(new LineStripMarker(this, context_, scene_node_));
}
break;
case visualization_msgs::Marker::LINE_LIST:
{
marker.reset(new LineListMarker(this, context_, scene_node_));
}
break;
case visualization_msgs::Marker::SPHERE_LIST:
case visualization_msgs::Marker::CUBE_LIST:
case visualization_msgs::Marker::POINTS:
{
marker.reset(new PointsMarker(this, context_, scene_node_));
}
break;
case visualization_msgs::Marker::TEXT_VIEW_FACING:
{
marker.reset(new TextViewFacingMarker(this, context_, scene_node_));
}
break;
case visualization_msgs::Marker::MESH_RESOURCE:
{
marker.reset(new MeshResourceMarker(this, context_, scene_node_));
}
break;

case visualization_msgs::Marker::TRIANGLE_LIST:
{
marker.reset(new TriangleListMarker(this, context_, scene_node_));
}
break;
default:
marker.reset(createMarker(message->type, this, context_, scene_node_));
if (!marker) {
ROS_ERROR( "Unknown marker type: %d", message->type );
}

markers_.insert(std::make_pair(MarkerID(message->ns, message->id), marker));
}

Expand Down
79 changes: 79 additions & 0 deletions src/rviz/default_plugin/marker_utils.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
/*
* Copyright (c) 2009, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "marker_utils.h"
#include "rviz/default_plugin/markers/shape_marker.h"
#include "rviz/default_plugin/markers/arrow_marker.h"
#include "rviz/default_plugin/markers/line_list_marker.h"
#include "rviz/default_plugin/markers/line_strip_marker.h"
#include "rviz/default_plugin/markers/points_marker.h"
#include "rviz/default_plugin/markers/text_view_facing_marker.h"
#include "rviz/default_plugin/markers/mesh_resource_marker.h"
#include "rviz/default_plugin/markers/triangle_list_marker.h"

namespace rviz
{

MarkerBase* createMarker(int marker_type, MarkerDisplay* owner, DisplayContext* context, Ogre::SceneNode* parent_node)
{
switch (marker_type) {
case visualization_msgs::Marker::CUBE:
case visualization_msgs::Marker::CYLINDER:
case visualization_msgs::Marker::SPHERE:
return new rviz::ShapeMarker(owner, context, parent_node);

case visualization_msgs::Marker::ARROW:
return new rviz::ArrowMarker(owner, context, parent_node);

case visualization_msgs::Marker::LINE_STRIP:
return new rviz::LineStripMarker(owner, context, parent_node);

case visualization_msgs::Marker::LINE_LIST:
return new rviz::LineListMarker(owner, context, parent_node);

case visualization_msgs::Marker::SPHERE_LIST:
case visualization_msgs::Marker::CUBE_LIST:
case visualization_msgs::Marker::POINTS:
return new rviz::PointsMarker(owner, context, parent_node);

case visualization_msgs::Marker::TEXT_VIEW_FACING:
return new rviz::TextViewFacingMarker(owner, context, parent_node);

case visualization_msgs::Marker::MESH_RESOURCE:
return new rviz::MeshResourceMarker(owner, context, parent_node);

case visualization_msgs::Marker::TRIANGLE_LIST:
return new rviz::TriangleListMarker(owner, context, parent_node);

default:
return nullptr;
}
}

} // namespace rviz
50 changes: 50 additions & 0 deletions src/rviz/default_plugin/marker_utils.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* Copyright (c) 2009, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#ifndef RVIZ_MARKER_UTILS_H
#define RVIZ_MARKER_UTILS_H

namespace Ogre
{
class SceneNode;
}

namespace rviz
{

class DisplayContext;
class MarkerDisplay;
class MarkerBase;

/** Create a marker of given type as declared in visualization_messages::Marker */
MarkerBase* createMarker(int marker_type, MarkerDisplay *owner, DisplayContext *context, Ogre::SceneNode *parent_node);

}

#endif

0 comments on commit 772da5f

Please sign in to comment.