Ajout Readme + Modif mineures interface

This commit is contained in:
Unknown 2018-08-10 16:57:26 +02:00
parent 1c72d90e9a
commit 3300e0efd3
100 changed files with 298 additions and 63 deletions

View file

@ -494,7 +494,7 @@ bool ASIFT_matcher::computeCenter(int& cx, int& cy) const
* threshold : Filtering coefficient. 1-Keep 68% of the keypoints / 2-Keep 95% of the keypoints / 3-Keep 99% of the keypoints. Default : 2.
* Return true if the filtering is done.
*/
bool ASIFT_matcher::distFilter(int threshold)
bool ASIFT_matcher::distFilter(float threshold)
{
if(_showInfo)
cout<<"filtering keypoint..."<<endl;
@ -565,6 +565,11 @@ bool ASIFT_matcher::distFilter(int threshold)
_num_matchings[i]=new_match.size();
}
//Update number of remaining points
_total_num_matchings = 0;
for(unsigned int i=0; i<_num_matchings.size();i++)
_total_num_matchings+=_num_matchings[i];
//Save filtered matchs
_matchings = filtered_match;

View file

@ -55,7 +55,7 @@ public:
unsigned int match(const vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1); //Perform matching between an image and the references.
bool computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const; //Compute the bounding rectangle of the mathcing keypoints.
bool computeCenter(int& cx, int& cy) const; //Compute the centroid of the matching keypoints.
bool distFilter(int threshold =2); //Perform a standard deviation filtering on the matching keypoints.
bool distFilter(float threshold =2); //Perform a standard deviation filtering on the matching keypoints.
bool saveReferences(const char* ref_path) const; //Save reference data necessary for the matching.
bool loadReferences(const char* ref_path); //Load reference data necessary for the matching.

View file

@ -7,7 +7,7 @@ int main(int argc, char **argv)
<< " *************************** ASIFT image matching **************************** " << std::endl
<< " ******************************************************************************* " << std::endl
<< "Usage: " << argv[0] << " imgIn.png [Tilt number option] [Filter option] [Resize option] " << std::endl
<< "- imgIn.png: input image (in PNG format). " << std::endl
<< "- imgIn.png: input image. " << std::endl
<< "- [Tilt number option: 1..(32+ ?)] : 7: Recommended / 1: no tilt. " << std::endl
<< "- [Filter option: 0..3]. Standard deviation filter coeff (1-68%/2-95%/3-99%). 0: no filtering (default). " << std::endl
<< "- [Resize option: 0/1]. 1: input images resize to 800x600 (default). 0: no resize. " << std::endl

View file

@ -1,3 +1,86 @@
# BaxterInterface
Bricks for an Rviz based interface for objective sending.
Maintainer: Antoine Harlé antoine.harle@etu.upmc.fr
## What is this ?
This is a ROS package implementing two working ROS modules : rviz_interface & asift_matching
It also include other ongoing non-ROS modules, mostly for test purposes.
### rviz_interface
This ROS modules implements markers and a panel for Rviz for sending StateSpace messages.
### asift_matching
* texte reference generation :
## Status
### Done
### Todo
REGLER LE PROBLEME DE FRAME ...
Problème dans le filtrage : nombre de points _> probleme de reset du nombre
## How to use it ?
### Requirements
* ROS Indigo (probably works in other versions too)
* PCL
* QT 5
* Eigen 3
### Usage
* Clone the repository to your catkin src
* catkin_make
#### Simple Rviz interface
* Run : roslaunch rviz_interface interface.launch
* Setup rviz :
- set fixed frame to camera_rgb_optical_frame.
- add an InteractiveMarker and set topic to /RvizInterface/update.
- add a Marker and set topic to vizualization_topic parameter.
- add the Rviz interface panel.
#### Rviz interface with simple moving tracker
* Run :
- roslaunch openni_launch openni.launch
- roslaunch rviz_interface interface_plannar_seg.launch
* Setup rviz :
- set fixed frame to camera_rgb_optical_frame.
- add an InteractiveMarker and set topic to /RvizInterface/update.
- add a Marker and set topic to vizualization_topic parameter.
- add the Rviz interface panel.
- add a PointCloud2 and set topic to /camera/depth_registered/points.
#### ASIFT matching (no vizualisation)
* Run :
- roslaunch openni_launch openni.launch
- asift_matching : roslaunch asift_matching asift_match.launch
#### ASIFT matching & Rviz interface
* Run :
- roslaunch openni_launch openni.launch
- roslaunch rviz_interface interface_matching.launch
* Setup rviz :
- set fixed frame to camera_rgb_optical_frame.
- add an InteractiveMarker and set topic to /RvizInterface/update.
- add a Marker and set topic to vizualization_topic parameter.
- add the Rviz interface panel.
- add a PointCloud2 and set topic to /camera/depth_registered/points.
### Parameters
* The topic names are defined as parameters in the launchfiles.
* rviz_interface parameters are defined as parameters in the rviz_interface launchfiles : Interface objects are defined by their names and types (0-Default, 1-Button, 2-2D object, 3-3D object) (see StateSpace.msg for more details).
* asift_matching parameters are defined as parameters in the asift_matching launchfiles :
-> References are defined by the path to the references files can be a txt file (faster - see texte reference generation in asift_matching section) or a series of images files (slower - currently not working).
-> Tracked object is defined by the object name (must be one of the interface object to work properly with rviz_interface).
-> Number of tilts is defined by an integer value (1-no tilt, 7-recommended value). Higher value means slower process.
-> Standaed deviation filter coefficient is defined by a real value. Keep (1-68%/2-95%/3-99%) of the points statistically. 0: no filtering (default).

View file

@ -1 +1,86 @@
# BaxterInterface
Bricks for an Rviz based interface for objective sending.
Maintainer: Antoine Harlé antoine.harle@etu.upmc.fr
## What is this ?
This is a ROS package implementing two working ROS modules : rviz_interface & asift_matching
It also include other ongoing non-ROS modules, mostly for test purposes.
### rviz_interface
This ROS modules implements markers and a panel for Rviz for sending StateSpace messages.
### asift_matching
* texte reference generation :
## Status
### Done
### Todo
REGLER LE PROBLEME DE FRAME ...
Problème dans le filtrage ?
## How to use it ?
### Requirements
* ROS Indigo (probably works in other versions too)
* PCL
* QT 5
* Eigen 3
### Usage
* Clone the repository to your catkin src
* catkin_make
#### Simple Rviz interface
* Run : roslaunch rviz_interface interface.launch
* Setup rviz :
- set fixed frame to camera_rgb_optical_frame.
- add an InteractiveMarker and set topic to /RvizInterface/update.
- add a Marker and set topic to vizualization_topic parameter.
- add the Rviz interface panel.
#### Rviz interface with simple moving tracker
* Run :
- roslaunch openni_launch openni.launch
- roslaunch rviz_interface interface_plannar_seg.launch
* Setup rviz :
- set fixed frame to camera_rgb_optical_frame.
- add an InteractiveMarker and set topic to /RvizInterface/update.
- add a Marker and set topic to vizualization_topic parameter.
- add the Rviz interface panel.
- add a PointCloud2 and set topic to /camera/depth_registered/points.
#### ASIFT matching (no vizualisation)
* Run :
- roslaunch openni_launch openni.launch
- asift_matching : roslaunch asift_matching asift_match.launch
#### ASIFT matching & Rviz interface
* Run :
- roslaunch openni_launch openni.launch
- roslaunch rviz_interface interface_matching.launch
* Setup rviz :
- set fixed frame to camera_rgb_optical_frame.
- add an InteractiveMarker and set topic to /RvizInterface/update.
- add a Marker and set topic to vizualization_topic parameter.
- add the Rviz interface panel.
- add a PointCloud2 and set topic to /camera/depth_registered/points.
### Parameters
* The topic names are defined as parameters in the launchfiles.
* rviz_interface parameters are defined as parameters in the rviz_interface launchfiles : Interface objects are defined by their names and types (0-Default, 1-Button, 2-2D object, 3-3D object) (see StateSpace.msg for more details).
* asift_matching parameters are defined as parameters in the asift_matching launchfiles :
-> References are defined by the path to the references files can be a txt file (faster - see texte reference generation in asift_matching section) or a series of images files (slower - currently not working).
-> Tracked object is defined by the object name (must be one of the interface object to work properly with rviz_interface).
-> Number of tilts is defined by an integer value (1-no tilt, 7-recommended value). Higher value means slower process.
-> Standaed deviation filter coefficient is defined by a real value. Keep (1-68%/2-95%/3-99%) of the points statistically. 0: no filtering (default).

View file

@ -1,12 +1,17 @@
<launch>
<!--Matcher Parameters/-->
<param name="tracked_object" value="6DOF"/>
<param name="num_tilt" type="int" value="2"/>
<param name="std_dev_filter_coeff" type="int" value="2"/>
<param name="std_dev_filter_coeff" type="double" value="2"/>
<!--Matcher References/-->
<param name="reference_path" value="$(find asift_matching)/reference_data/"/>
<param name="reference_txt_path" value="$(find asift_matching)/reference_data/book_references.txt"/>
<!--rosparam param="reference_data">[
"$(find asift_matching)/reference_data/train_image_000.png",
"$(find asift_matching)/reference_data/train_image_001.png"]</rosparam-->
<rosparam param="reference_data">[
"train_image_000.png",
"train_image_001.png"]
</rosparam>
<!--Topics/-->
<param name="object_center_topic" value="/object_center"/>
<param name="image_topic" value="/camera/rgb/image_raw"/>
<param name="pointcloud_topic" value="/camera/depth_registered/points"/>

View file

@ -1,12 +1,17 @@
<launch>
<!--Matcher Parameters/-->
<param name="tracked_object" value="6DOF"/>
<param name="num_tilt" type="int" value="2"/>
<param name="std_dev_filter_coeff" type="int" value="2"/>
<param name="std_dev_filter_coeff" type="float" value="2"/>
<!--Matcher References/-->
<param name="reference_path" value="$(find asift_matching)/reference_data/"/>
<param name="reference_txt_path" value="$(find asift_matching)/reference_data/book_references.txt"/>
<!--rosparam param="reference_data">[
"$(find asift_matching)/reference_data/train_image_000.png",
"$(find asift_matching)/reference_data/train_image_001.png"]</rosparam-->
<rosparam param="reference_data">[
"train_image_000.png",
"train_image_001.png"]
</rosparam>
<!--Topics/-->
<param name="object_center_topic" value="/object_center"/>
<param name="image_topic" value="/camera/rgb/image_raw"/>
<param name="pointcloud_topic" value="/camera/depth_registered/points"/>

View file

@ -494,7 +494,7 @@ bool ASIFT_matcher::computeCenter(int& cx, int& cy) const
* threshold : Filtering coefficient. 1-Keep 68% of the keypoints / 2-Keep 95% of the keypoints / 3-Keep 99% of the keypoints. Default : 2.
* Return true if the filtering is done.
*/
bool ASIFT_matcher::distFilter(int threshold)
bool ASIFT_matcher::distFilter(float threshold)
{
if(_showInfo)
cout<<"filtering keypoint..."<<endl;
@ -565,6 +565,11 @@ bool ASIFT_matcher::distFilter(int threshold)
_num_matchings[i]=new_match.size();
}
//Update number of remaining points
_total_num_matchings = 0;
for(unsigned int i=0; i<_num_matchings.size();i++)
_total_num_matchings+=_num_matchings[i];
//Save filtered matchs
_matchings = filtered_match;

View file

@ -55,7 +55,7 @@ public:
unsigned int match(const vector<float>& image, unsigned int w, unsigned int h, unsigned int num_tilts =1); //Perform matching between an image and the references.
bool computeROI(int& x, int& y, unsigned int& h, unsigned int& w) const; //Compute the bounding rectangle of the mathcing keypoints.
bool computeCenter(int& cx, int& cy) const; //Compute the centroid of the matching keypoints.
bool distFilter(int threshold =2); //Perform a standard deviation filtering on the matching keypoints.
bool distFilter(float threshold =2); //Perform a standard deviation filtering on the matching keypoints.
bool saveReferences(const char* ref_path) const; //Save reference data necessary for the matching.
bool loadReferences(const char* ref_path); //Load reference data necessary for the matching.

View file

@ -7,15 +7,16 @@
#include "ROS_matcher.hpp"
//TODO : Regler le problème du chergements des images
ROS_matcher::ROS_matcher(): _status(MATCHER_STATUS_WAITING_INIT)
{
std::string center_topic, image_topic, pointcloud_topic, reference_txt_path;
std::string center_topic, image_topic, pointcloud_topic, reference_txt_path, reference_path;
std::vector<std::string> reference_data_paths;
//Load Param
_nh.param<std::string>("tracked_object", tracked_object, "Object");
_nh.param<int>("num_tilt", _num_tilt, 8);
_nh.param<int>("std_dev_filter_coeff", _filter_coeff, 0);
_nh.param<float>("std_dev_filter_coeff", _filter_coeff, 0);
_nh.param<std::string>("object_center_topic", center_topic,"/ASIFT_matcher/object_center");
_nh.param<std::string>("image_topic", image_topic,"/camera/rgb/image_raw");
@ -34,26 +35,30 @@ ROS_matcher::ROS_matcher(): _status(MATCHER_STATUS_WAITING_INIT)
matcher.showInfo(false);
//Load References
if(_nh.getParam("reference_txt_path", reference_txt_path))
_nh.param<std::string>("reference_path", reference_path); //BUG sur reference path ?
ROS_INFO("Ref path : %s", reference_path.c_str());
if(_nh.getParam("reference_txt_path", reference_txt_path) && matcher.loadReferences(reference_txt_path.c_str()))
{
if(matcher.loadReferences(reference_txt_path.c_str()))
_status = MATCHER_STATUS_IDLE;
ROS_INFO("Loaded reference from %s",reference_txt_path.c_str());
}
else if(_nh.getParam("reference_data", reference_data_paths))
{
for(unsigned int i=0; i<reference_data_paths.size(); i++)
matcher.addReference(reference_data_paths[i].c_str(),_num_tilt);
if(matcher.getNbRef()>0)
_status = MATCHER_STATUS_IDLE;
{
matcher.addReference((reference_path+reference_data_paths[i]).c_str(),_num_tilt);
ROS_INFO("Loaded reference from %s",(reference_path+reference_data_paths[i]).c_str());
}
}
else
{
ROS_WARN("No reference data to initialize matcher.");
}
if(_status == MATCHER_STATUS_IDLE)
ROS_INFO("Matcher Ready ! (%d references from %s)",matcher.getNbRef(), reference_txt_path.c_str());
if(matcher.getNbRef()>0)
{
_status = MATCHER_STATUS_IDLE;
ROS_INFO("Matcher Ready ! (%d references)",matcher.getNbRef());
}
}
ROS_matcher::~ROS_matcher()
@ -113,7 +118,7 @@ void ROS_matcher::cameraCallback(const sensor_msgs::Image::ConstPtr& image_msg,
// geometry_msgs::PointStamped center_msg;
rviz_interface::NamedPoint center_msg;
matcher.distFilter(_filter_coeff);
ROS_INFO("Filtered points : %d", matcher.getNbMatch());
if(matcher.computeCenter(cx, cy))
{
//Conversions des donnée d'entrée en PCL

View file

@ -50,7 +50,8 @@ protected:
message_filters::Synchronizer<MySyncPolicy>* Timesync;
//Matcher
int _num_tilt, _filter_coeff; //Parameters of the ASIFT_matcher
int _num_tilt; //Number of tilts
float _filter_coeff; //Filter parameter
ASIFT_matcher matcher; //Matcher
MATCHER_STATUS _status; //Matcher status

View file

@ -0,0 +1,17 @@
<launch>
<node name="rviz" pkg="rviz" type="rviz"/>
<!--Interface/-->
<!--Objects/-->
<param name="frame_id" value="/map"/>
<rosparam param="object_names"> ["Foo", "KungFoo", "Panda", "Boo"]</rosparam>
<rosparam param="object_types"> [3, 2, 1, 0]</rosparam>
<!--Topics/-->
<param name="objective_topic" value="/RvizInterface/state_objective"/>
<param name="vizualization_topic" value="/RvizInterface/visual_marker"/>
<param name="config_topic" value="/RvizInterface/interface_config"/>
<node name="RvizInterface" pkg="rviz_interface" type="RvizInterface" output="screen"/>
</launch>

View file

@ -0,0 +1,16 @@
<launch>
<node name="rviz" pkg="rviz" type="rviz"/>
<!--Interface/-->
<!--Objects/-->
<rosparam param="object_names"> ["Foo", "KungFoo", "Panda", "Boo"]</rosparam>
<rosparam param="object_types"> [3, 2, 1, 0]</rosparam>
<!--Topics/-->
<param name="objective_topic" value="/RvizInterface/state_objective"/>
<param name="vizualization_topic" value="/RvizInterface/visual_marker"/>
<param name="config_topic" value="/RvizInterface/interface_config"/>
<node name="RvizInterface" pkg="rviz_interface" type="RvizInterface" output="screen"/>
</launch>

View file

@ -1,11 +1,12 @@
<launch>
<node name="rviz" pkg="rviz" type="rviz"/>
<!--Objects/-->
<rosparam param="tracked_object_names"> ["Foo", "KungFoo", "Panda", "Boo"]</rosparam>
<rosparam param="tracked_object_types"> [3, 2, 1, 0]</rosparam>
<!--Interface/-->
<!--Objects/-->
<rosparam param="object_names"> ["Foo", "KungFoo", "Panda", "Boo"]</rosparam>
<rosparam param="object_types"> [3, 2, 1, 0]</rosparam>
<!--Topics/-->
<param name="objective_topic" value="/RvizInterface/state_objective"/>
<param name="vizualization_topic" value="/RvizInterface/visual_marker"/>
<param name="config_topic" value="/RvizInterface/interface_config"/>
@ -13,13 +14,19 @@
<node name="RvizInterface" pkg="rviz_interface" type="RvizInterface" output="screen"/>
<!--Matcher/-->
<!--Matcher Parameters/-->
<param name="tracked_object" value="Foo"/>
<param name="num_tilt" type="int" value="8"/>
<param name="std_dev_filter_coeff" type="int" value="2"/>
<param name="reference_txt_path" value="$(find asift_matching)/reference_data/robobo_references.txt"/>
<!--rosparam param="reference_data">[
"$(find asift_matching)/reference_data/train_image_000.png",
"$(find asift_matching)/reference_data/train_image_001.png"]</rosparam-->
<param name="std_dev_filter_coeff" type="double" value="2"/>
<!--Matcher References/-->
<param name="reference_path" value="$(find asift_matching)/reference_data/"/>
<param name="reference_txt_path" value="$(find asift_matching)/reference_data/book_references.txt"/>
<rosparam param="reference_data">[
"train_image_000.png",
"train_image_001.png"]
</rosparam>
<!--Topics/-->
<param name="object_center_topic" value="/object_center"/>
<param name="image_topic" value="/camera/rgb/image_raw"/>
<param name="pointcloud_topic" value="/camera/depth_registered/points"/>

View file

@ -2,6 +2,11 @@
<node name="rviz" pkg="rviz" type="rviz"/>
<!--Interface/-->
<!--Objects/-->
<rosparam param="object_names"> ["Foo", "KungFoo", "Panda", "Boo"]</rosparam>
<rosparam param="object_types"> [3, 2, 1, 0]</rosparam>
<!--Topics/-->
<param name="objective_topic" value="/RvizInterface/state_objective"/>
<param name="vizualization_topic" value="/RvizInterface/visual_marker"/>
<param name="config_topic" value="/RvizInterface/interface_config"/>
@ -9,15 +14,19 @@
<node name="RvizInterface" pkg="rviz_interface" type="RvizInterface" output="screen"/>
<!--Matcher/-->
<rosparam param="tracked_object_names"> ["Foo", "KungFoo", "Panda", "Boo"]</rosparam>
<rosparam param="tracked_object_types"> [3, 2, 1, 0]</rosparam>
<!--Matcher Parameters/-->
<param name="tracked_object" value="Foo"/>
<param name="num_tilt" type="int" value="8"/>
<param name="std_dev_filter_coeff" type="int" value="2"/>
<param name="reference_txt_path" value="$(find asift_matching)/reference_data/robobo_references.txt"/>
<!--rosparam param="reference_data">[
"$(find asift_matching)/reference_data/train_image_000.png",
"$(find asift_matching)/reference_data/train_image_001.png"]</rosparam-->
<param name="std_dev_filter_coeff" type="double" value="0.5"/>
<!--Matcher References/-->
<param name="reference_path" value="$(find asift_matching)/reference_data/"/>
<param name="reference_txt_path" value="$(find asift_matching)/reference_data/book_references.txt"/>
<rosparam param="reference_data">[
"train_image_000.png",
"train_image_001.png"]
</rosparam>
<!--Topics/-->
<param name="object_center_topic" value="/object_center"/>
<param name="image_topic" value="/camera/rgb/image_raw"/>
<param name="pointcloud_topic" value="/camera/depth_registered/points"/>

View file

@ -2,8 +2,8 @@
<node name="rviz" pkg="rviz" type="rviz"/>
<!--Interface/-->
<rosparam param="tracked_object_names"> ["6DOF"]</rosparam>
<rosparam param="tracked_object_types"> [0]</rosparam>
<rosparam param="object_names"> ["6DOF"]</rosparam>
<rosparam param="object_types"> [0]</rosparam>
<node name="RvizInterface" pkg="rviz_interface" type="RvizInterface"/>

View file

@ -9,7 +9,7 @@
unsigned int InteractiveObject::nextObjectID = 1;
//Constructeur
InteractiveObject::InteractiveObject(interactive_markers::InteractiveMarkerServer* server, const std::string& name, unsigned int type, unsigned int shape = Marker::CUBE, const tf::Vector3& position = tf::Vector3(0,0,0)) : _name(name), _type(type), _server(server), _showVisuals(true), _followObject(true)
InteractiveObject::InteractiveObject(interactive_markers::InteractiveMarkerServer* server, const std::string& name, unsigned int type, unsigned int shape = Marker::CUBE, const tf::Vector3& position) : _name(name), _type(type), _server(server), _showVisuals(true), _followObject(true)
{
_objectID = nextObjectID++;
_state.name = name;
@ -31,7 +31,7 @@ InteractiveObject::InteractiveObject(interactive_markers::InteractiveMarkerServe
}
//Construit un InteractiveMarker
void InteractiveObject::createInteractiveMarker(Marker& marker, const tf::Vector3& position = tf::Vector3(0,0,0))
void InteractiveObject::createInteractiveMarker(Marker& marker, const tf::Vector3& position)
{
//// Création d'un marker interactif ////
// _int_marker.header.frame_id = "/map"; //Par défaut

View file

@ -36,10 +36,10 @@ protected:
ros::Publisher* _visual_pub;
public:
InteractiveObject(interactive_markers::InteractiveMarkerServer* server, const std::string& name, unsigned int type, unsigned int shape, const tf::Vector3& position);
InteractiveObject(interactive_markers::InteractiveMarkerServer* server, const std::string& name, unsigned int type, unsigned int shape, const tf::Vector3& position = tf::Vector3(0,0,0));
//Construit un InteractiveMarker
void createInteractiveMarker(Marker& marker, const tf::Vector3& position);
void createInteractiveMarker(Marker& marker, const tf::Vector3& position = tf::Vector3(0,0,0));
//Fonction callback du serveur d' InteractiveMarker
void processFeedback( const InteractiveMarkerFeedbackConstPtr &feedback );

View file

@ -13,6 +13,7 @@ RvizInterface::RvizInterface(): _server("RvizInterface")
std::string objective_topic, vizualization_topic, config_topic, position_topic;
std::vector<std::string> object_names;
std::vector<int> object_types;
std::string frame_id;
//Load Topics param
_n.param<std::string>("objective_topic", objective_topic,"/RvizInterface/state_objective");
@ -29,8 +30,9 @@ RvizInterface::RvizInterface(): _server("RvizInterface")
_position_sub = _n.subscribe(position_topic, 1, &RvizInterface::positionCallback, this);
//Load objects
_n.getParam("tracked_object_names",object_names);
_n.getParam("tracked_object_types",object_types);
_n.param<std::string>("frame_id", frame_id,"/map");
_n.getParam("object_names",object_names);
_n.getParam("object_types",object_types);
int names_size = object_names.size();
@ -57,7 +59,7 @@ RvizInterface::RvizInterface(): _server("RvizInterface")
break;
case 1:
_objects.push_back(new InteractiveObject(&_server, object_names[i], (int) rviz_interface::StateSpace::STATE_BOOL, (int) visualization_msgs::Marker::SPHERE, tf::Vector3(0,0,0)));
_objects[i]->addButtoncontrol();
// _objects[i]->addButtoncontrol();
break;
case 2:
_objects.push_back(new InteractiveObject(&_server, object_names[i], (int) rviz_interface::StateSpace::STATE_2D, (int) visualization_msgs::Marker::SPHERE, tf::Vector3(0,0,0)));
@ -69,16 +71,6 @@ RvizInterface::RvizInterface(): _server("RvizInterface")
break;
}
}
// _objects.push_back(new InteractiveObject(&_server, object_name, (int) rviz_interface::StateSpace::STATE_3D, (int) visualization_msgs::Marker::SPHERE, tf::Vector3(0,0,0)));
// _objects[0]->add6DOFcontrol();
// _objects.push_back(new InteractiveObject(&_server, "3DOF", (int) rviz_interface::StateSpace::STATE_2D, (int) visualization_msgs::Marker::SPHERE, tf::Vector3(0,0,0)));
// _objects[1]->add3DOFcontrol();
// _objects.push_back(new InteractiveObject(&_server, "3DOF 2", (int) rviz_interface::StateSpace::STATE_2D, (int) visualization_msgs::Marker::SPHERE, tf::Vector3(-1,1,0)));
// _objects[2]->add3DOFcontrol(tf::Vector3(0.5,0.5,0));
// _objects.push_back(new InteractiveObject(&_server, "Button", (int) rviz_interface::StateSpace::STATE_3D, (int) visualization_msgs::Marker::SPHERE, tf::Vector3(1,-1,0)));
for(unsigned int i=0;i<_objects.size();i++)
{