|
From: <tf...@us...> - 2009-01-27 20:57:09
|
Revision: 10270
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=10270&view=rev
Author: tfoote
Date: 2009-01-27 20:57:04 +0000 (Tue, 27 Jan 2009)
Log Message:
-----------
moving VisualizationMarker message to robot msgs from std_msgs ros#447
Modified Paths:
--------------
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp
pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
pkg/trunk/motion_planning/kinematic_planning/src/state_validity_monitor.cpp
pkg/trunk/motion_planning/test_collision_space/manifest.xml
pkg/trunk/motion_planning/test_collision_space/src/test_cs.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.cpp
pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.h
pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp
Added Paths:
-----------
pkg/trunk/prcore/robot_msgs/msg/VisualizationMarker.msg
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_pan_tilt_controller.h 2009-01-27 20:57:04 UTC (rev 10270)
@@ -49,7 +49,7 @@
#include <robot_msgs/JointCmd.h>
#include <robot_srvs/GetJointCmd.h>
#include <std_msgs/PointStamped.h>
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
// Math utils
#include <math.h>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/head_servoing_controller.h 2009-01-27 20:57:04 UTC (rev 10270)
@@ -49,7 +49,7 @@
#include <robot_msgs/JointCmd.h>
#include <robot_srvs/GetJointCmd.h>
#include <std_msgs/PointStamped.h>
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
// Math utils
#include <math.h>
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_pan_tilt_controller.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -194,7 +194,7 @@
//services
node_->advertiseService(service_prefix_ + "/get_command_array", &HeadPanTiltControllerNode::getJointCmd, this);
guard_get_command_array_.set(service_prefix_ + "/get_command_array");
- node_->advertise<std_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
return true;
}
@@ -340,7 +340,7 @@
c_->setJointCmd(pos,names);
- std_msgs::VisualizationMarker marker;
+ robot_msgs::VisualizationMarker marker;
marker.header.frame_id = "stereo";
marker.id = 0;
marker.type = 0;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/head_servoing_controller.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -219,7 +219,7 @@
//services
node_->advertiseService(service_prefix_ + "/get_command_array", &HeadServoingControllerNode::getJointCmd, this);
guard_get_command_array_.set(service_prefix_ + "/get_command_array");
- node_->advertise<std_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
return true;
}
@@ -357,7 +357,7 @@
c_->setJointCmd(pos,names);
- std_msgs::VisualizationMarker marker;
+ robot_msgs::VisualizationMarker marker;
marker.header.frame_id = "stereo";
marker.id = 0;
marker.type = 0;
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/endeffector_constraint_controller.h 2009-01-27 20:57:04 UTC (rev 10270)
@@ -47,7 +47,7 @@
#include "Eigen/LU"
#include "Eigen/Core"
#include "robot_kinematics/robot_kinematics.h"
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
namespace controller {
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/endeffector_constraint_controller.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -319,7 +319,7 @@
node_->subscribe(topic_ + "/command", wrench_msg_,
&EndeffectorConstraintControllerNode::command, this, 1);
guard_command_.set(topic_ + "/command");
- node_->advertise<std_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node_->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
return true;
@@ -334,10 +334,10 @@
if (count%100==0)
{
- std_msgs::VisualizationMarker marker;
+ robot_msgs::VisualizationMarker marker;
marker.header.frame_id = "torso_lift_link";
marker.id = 0;
- marker.type = std_msgs::VisualizationMarker::CUBE;
+ marker.type = robot_msgs::VisualizationMarker::CUBE;
marker.action = 0;
marker.x = 0.6;
marker.y = 0;
@@ -358,10 +358,10 @@
if (count%100==0)
{
- std_msgs::VisualizationMarker marker;
+ robot_msgs::VisualizationMarker marker;
marker.header.frame_id = "torso_lift_link";
marker.id = 1;
- marker.type = std_msgs::VisualizationMarker::SPHERE;
+ marker.type = robot_msgs::VisualizationMarker::SPHERE;
marker.action = 0;
marker.x = 0.6;
marker.y = 0;
Modified: pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp
===================================================================
--- pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/mapping/collision_map/src/collision_map_buffer.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -46,7 +46,7 @@
#include <std_msgs/Point.h>
#include <std_msgs/PointCloud.h>
#include <std_msgs/PoseStamped.h>
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
#include <Eigen/Core>
#include <cloud_geometry/point.h>
@@ -184,7 +184,7 @@
subtract_object_ = false;
m_id_ = 0;
- advertise<std_msgs::VisualizationMarker>("visualizationMarker", 100);
+ advertise<robot_msgs::VisualizationMarker>("visualizationMarker", 100);
}
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
Modified: pkg/trunk/motion_planning/kinematic_planning/src/state_validity_monitor.cpp
===================================================================
--- pkg/trunk/motion_planning/kinematic_planning/src/state_validity_monitor.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/motion_planning/kinematic_planning/src/state_validity_monitor.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -89,7 +89,7 @@
#include "kinematic_planning/CollisionSpaceMonitor.h"
#include <std_msgs/Byte.h>
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
#include <iostream>
#include <sstream>
@@ -109,7 +109,7 @@
id_(0)
{
advertise<std_msgs::Byte>("state_validity", 1);
- advertise<std_msgs::VisualizationMarker>("visualizationMarker", 10240);
+ advertise<robot_msgs::VisualizationMarker>("visualizationMarker", 10240);
}
virtual ~StateValidityMonitor(void)
@@ -168,12 +168,12 @@
void sendPoint(double x, double y, double z, double radius, const rostools::Header &header)
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
mk.header = header;
mk.id = id_++;
- mk.type = std_msgs::VisualizationMarker::SPHERE;
- mk.action = std_msgs::VisualizationMarker::ADD;
+ mk.type = robot_msgs::VisualizationMarker::SPHERE;
+ mk.action = robot_msgs::VisualizationMarker::ADD;
mk.x = x;
mk.y = y;
mk.z = z;
@@ -196,12 +196,12 @@
void delPoint(int id, const rostools::Header &header)
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
mk.header = header;
mk.id = id;
- mk.type = std_msgs::VisualizationMarker::SPHERE;
- mk.action = std_msgs::VisualizationMarker::DELETE;
+ mk.type = robot_msgs::VisualizationMarker::SPHERE;
+ mk.action = robot_msgs::VisualizationMarker::DELETE;
publish("visualizationMarker", mk);
}
Modified: pkg/trunk/motion_planning/test_collision_space/manifest.xml
===================================================================
--- pkg/trunk/motion_planning/test_collision_space/manifest.xml 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/motion_planning/test_collision_space/manifest.xml 2009-01-27 20:57:04 UTC (rev 10270)
@@ -12,6 +12,7 @@
<depend package="rostime"/>
<depend package="tf"/>
<depend package="std_msgs"/>
+ <depend package="robot_msgs"/>
<depend package="collision_space"/>
<depend package="random_utils"/>
Modified: pkg/trunk/motion_planning/test_collision_space/src/test_cs.cpp
===================================================================
--- pkg/trunk/motion_planning/test_collision_space/src/test_cs.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/motion_planning/test_collision_space/src/test_cs.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -39,7 +39,7 @@
#include <ros/time.h>
#include <collision_space/environmentODE.h>
#include <algorithm>
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
#include <rostools/Time.h>
#include <tf/transform_broadcaster.h>
#include <collision_space/util.h>
@@ -55,7 +55,7 @@
TestVM(void) : ros::Node("TVM")
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
advertise("visualizationMarker",
mk,
&TestVM::subCb,
@@ -86,15 +86,15 @@
void sendPoint(double x, double y, double z)
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
mk.header.stamp = m_tm;
mk.header.frame_id = "map";
mk.id = m_id++;
- mk.type = std_msgs::VisualizationMarker::SPHERE;
- mk.action = std_msgs::VisualizationMarker::ADD;
+ mk.type = robot_msgs::VisualizationMarker::SPHERE;
+ mk.action = robot_msgs::VisualizationMarker::ADD;
mk.x = x;
mk.y = y;
mk.z = z;
@@ -129,7 +129,7 @@
}
void setShapeTransformAndMarker(collision_space::bodies::Shape *s,
- std_msgs::VisualizationMarker &mk)
+ robot_msgs::VisualizationMarker &mk)
{
btTransform t;
@@ -151,7 +151,7 @@
mk.header.frame_id = "map";
mk.id = m_id++;
- mk.action = std_msgs::VisualizationMarker::ADD;
+ mk.action = robot_msgs::VisualizationMarker::ADD;
mk.x = x;
mk.y = y;
@@ -175,10 +175,10 @@
for (int i = 0 ; i < TEST_TIMES ; ++i)
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
setShapeTransformAndMarker(s, mk);
- mk.type = std_msgs::VisualizationMarker::SPHERE;
+ mk.type = robot_msgs::VisualizationMarker::SPHERE;
mk.xScale = radius[0]*2.0;
mk.yScale = radius[0]*2.0;
mk.zScale = radius[0]*2.0;
@@ -199,10 +199,10 @@
for (int i = 0 ; i < TEST_TIMES ; ++i)
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
setShapeTransformAndMarker(s, mk);
- mk.type = std_msgs::VisualizationMarker::CUBE;
+ mk.type = robot_msgs::VisualizationMarker::CUBE;
mk.xScale = dims[0]; // length
mk.yScale = dims[1]; // width
mk.zScale = dims[2]; // height
@@ -223,10 +223,10 @@
for (int i = 0 ; i < TEST_TIMES ; ++i)
{
- std_msgs::VisualizationMarker mk;
+ robot_msgs::VisualizationMarker mk;
setShapeTransformAndMarker(s, mk);
- mk.type = std_msgs::VisualizationMarker::CUBE;
+ mk.type = robot_msgs::VisualizationMarker::CUBE;
mk.xScale = dims[1] * 2.0; // radius
mk.yScale = dims[1] * 2.0; // radius
mk.zScale = dims[0]; //length
Added: pkg/trunk/prcore/robot_msgs/msg/VisualizationMarker.msg
===================================================================
--- pkg/trunk/prcore/robot_msgs/msg/VisualizationMarker.msg (rev 0)
+++ pkg/trunk/prcore/robot_msgs/msg/VisualizationMarker.msg 2009-01-27 20:57:04 UTC (rev 10270)
@@ -0,0 +1,35 @@
+#
+# Visualization Marker message
+# For inserting pre-made objects into the visualization
+#
+
+byte ARROW=0
+byte CUBE=1
+byte SPHERE=2
+byte ROBOT=3
+byte LINE_STRIP=4
+byte CYLINDER=5
+
+byte ADD=0
+byte MODIFY=0
+byte DELETE=2
+
+Header header # header for time/frame information
+int32 id # object ID useful for manipulating and deleting the object later
+int32 type # Type of object
+int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object
+float32 x # x location of the object
+float32 y # y location of the object
+float32 z # z location of the object
+float32 roll # roll of the object
+float32 pitch # pitch of the object
+float32 yaw # yaw of the object
+float32 xScale # scale of the object in the x direction (1 does not change size) (default sizes are usually 1 meter square)
+float32 yScale # scale in y direction
+float32 zScale # scale in z direction
+int32 alpha # alpha (0-255) (amount of transparency, 255 is opaque)
+int32 r # red color value (0-255) (if available)
+int32 g # green color value
+int32 b # blue color value
+#These are only used if the object type is LINE_STRIP
+std_msgs/Position[] points
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -59,7 +59,7 @@
kinematic_model_ = new planning_models::KinematicModel();
kinematic_model_->setVerbose( false );
- notifier_ = new tf::MessageNotifier<std_msgs::VisualizationMarker>(tf_, ros_node_, boost::bind(&MarkerDisplay::incomingMarker, this, _1), "", "", 100);
+ notifier_ = new tf::MessageNotifier<robot_msgs::VisualizationMarker>(tf_, ros_node_, boost::bind(&MarkerDisplay::incomingMarker, this, _1), "", "", 100);
}
MarkerDisplay::~MarkerDisplay()
@@ -138,11 +138,11 @@
{
switch ( message->action )
{
- case std_msgs::VisualizationMarker::ADD:
+ case robot_msgs::VisualizationMarker::ADD:
processAdd( message );
break;
- case std_msgs::VisualizationMarker::DELETE:
+ case robot_msgs::VisualizationMarker::DELETE:
processDelete( message );
break;
@@ -178,7 +178,7 @@
{
switch ( message->type )
{
- case std_msgs::VisualizationMarker::CUBE:
+ case robot_msgs::VisualizationMarker::CUBE:
{
ogre_tools::Shape* cube = new ogre_tools::Shape( ogre_tools::Shape::Cube, scene_manager_, scene_node_ );
@@ -186,7 +186,7 @@
}
break;
- case std_msgs::VisualizationMarker::CYLINDER:
+ case robot_msgs::VisualizationMarker::CYLINDER:
{
ogre_tools::Shape* cylinder = new ogre_tools::Shape( ogre_tools::Shape::Cylinder, scene_manager_, scene_node_ );
@@ -194,7 +194,7 @@
}
break;
- case std_msgs::VisualizationMarker::SPHERE:
+ case robot_msgs::VisualizationMarker::SPHERE:
{
ogre_tools::Shape* sphere = new ogre_tools::Shape( ogre_tools::Shape::Sphere, scene_manager_, scene_node_ );
@@ -202,13 +202,13 @@
}
break;
- case std_msgs::VisualizationMarker::ARROW:
+ case robot_msgs::VisualizationMarker::ARROW:
{
object = new ogre_tools::Arrow( scene_manager_, scene_node_, 0.8, 0.5, 0.2, 1.0 );
}
break;
- case std_msgs::VisualizationMarker::ROBOT:
+ case robot_msgs::VisualizationMarker::ROBOT:
{
Robot* robot = new Robot( scene_manager_ );
robot->load( urdf_, false, true );
@@ -218,7 +218,7 @@
}
break;
- case std_msgs::VisualizationMarker::LINE_STRIP:
+ case robot_msgs::VisualizationMarker::LINE_STRIP:
{
ogre_tools::BillboardLine* line = new ogre_tools::BillboardLine( scene_manager_, scene_node_ );
object = line;
@@ -292,7 +292,7 @@
object->setColor( message->r / 255.0f, message->g / 255.0f, message->b / 255.0f, message->alpha / 255.0f );
object->setUserData( Ogre::Any( (void*)this ) );
- if ( message->type == std_msgs::VisualizationMarker::LINE_STRIP )
+ if ( message->type == robot_msgs::VisualizationMarker::LINE_STRIP )
{
ogre_tools::BillboardLine* line = dynamic_cast<ogre_tools::BillboardLine*>(object);
ROS_ASSERT( line );
Modified: pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.h
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.h 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/visualization/ogre_visualizer/src/ogre_visualizer/displays/marker_display.h 2009-01-27 20:57:04 UTC (rev 10270)
@@ -34,7 +34,7 @@
#include <map>
-#include <std_msgs/VisualizationMarker.h>
+#include <robot_msgs/VisualizationMarker.h>
#include <boost/thread/mutex.hpp>
#include <boost/shared_ptr.hpp>
@@ -76,7 +76,7 @@
* \class MarkerDisplay
* \brief Displays "markers" sent in by other ROS nodes on the "visualizationMarker" topic
*
- * Markers come in as std_msgs::VisualizationMarker messages. See the VisualizationMarker message for more information.
+ * Markers come in as robot_msgs::VisualizationMarker messages. See the VisualizationMarker message for more information.
*/
class MarkerDisplay : public Display
{
@@ -114,7 +114,7 @@
*/
void clearMarkers();
- typedef boost::shared_ptr<std_msgs::VisualizationMarker> MarkerPtr;
+ typedef boost::shared_ptr<robot_msgs::VisualizationMarker> MarkerPtr;
/**
* \brief Processes a marker message
@@ -150,7 +150,7 @@
, message_(message)
{}
ogre_tools::Object* object_;
- boost::shared_ptr<std_msgs::VisualizationMarker> message_;
+ boost::shared_ptr<robot_msgs::VisualizationMarker> message_;
};
typedef std::map<int, MarkerInfo> M_IDToMarker;
@@ -166,7 +166,7 @@
robot_desc::URDF* urdf_;
planning_models::KinematicModel* kinematic_model_;
- tf::MessageNotifier<std_msgs::VisualizationMarker>* notifier_;
+ tf::MessageNotifier<robot_msgs::VisualizationMarker>* notifier_;
};
} // namespace ogre_vis
Modified: pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp
===================================================================
--- pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp 2009-01-27 20:41:49 UTC (rev 10269)
+++ pkg/trunk/visualization/ogre_visualizer/src/test/marker_test.cpp 2009-01-27 20:57:04 UTC (rev 10270)
@@ -1,6 +1,6 @@
#include "ros/node.h"
-#include "std_msgs/VisualizationMarker.h"
+#include "robot_msgs/VisualizationMarker.h"
int main( int argc, char** argv )
{
@@ -13,17 +13,17 @@
usleep( 10000 );
}
- node->advertise<std_msgs::VisualizationMarker>( "visualizationMarker", 0 );
+ node->advertise<robot_msgs::VisualizationMarker>( "visualizationMarker", 0 );
usleep( 1000000 );
for ( int i = -50; i < 50; ++i )
{
- std_msgs::VisualizationMarker marker;
+ robot_msgs::VisualizationMarker marker;
marker.header.frame_id = "map";
marker.header.stamp = ros::Time();
marker.id = i;
- marker.type = std_msgs::VisualizationMarker::ARROW;
+ marker.type = robot_msgs::VisualizationMarker::ARROW;
marker.action = 0;
marker.x = 1;
marker.y = (i*2);
@@ -41,11 +41,11 @@
node->publish( "visualizationMarker", marker );
}
- std_msgs::VisualizationMarker line_marker;
+ robot_msgs::VisualizationMarker line_marker;
line_marker.header.frame_id = "map";
line_marker.header.stamp = ros::Time();
line_marker.id = 1000;
- line_marker.type = std_msgs::VisualizationMarker::LINE_STRIP;
+ line_marker.type = robot_msgs::VisualizationMarker::LINE_STRIP;
line_marker.action = 0;
line_marker.x = 0;
line_marker.y = 0;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|