Skip to content

Commit

Permalink
[PointCloud] Add idl method to refresh octree in gepetto-viewer.
Browse files Browse the repository at this point in the history
  • Loading branch information
Florent Lamiraux committed Sep 30, 2022
1 parent e23071a commit 5110cfe
Show file tree
Hide file tree
Showing 3 changed files with 28 additions and 16 deletions.
2 changes: 2 additions & 0 deletions idl/hpp/agimus_idl/point-cloud.idl
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,8 @@ module hpp {
void setDistanceBounds(in double min, in double max) raises(Error);
/// Set whether to display octree in gepetto-viewer
void setDisplay(in boolean flag) raises(Error);
/// Refresh octree in gepetto-viewer
void refreshOctree() raises(Error);
}; // interface PointCloud
}; // module agimus_idl
}; // module hpp
Expand Down
9 changes: 5 additions & 4 deletions include/hpp/agimus/point-cloud.hh
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,8 @@ namespace hpp {
void setDistanceBounds(value_type min, value_type max);
/// Set whether to display octree in gepetto-viewer
void setDisplay(bool flag);
/// Refresh octree in gepetto-viewer
void refreshOctree();
/// Callback to the point cloud topic
void pointCloudCb(const sensor_msgs::PointCloud2ConstPtr& data);
/// Set three points belonging to the object plan, in the object frame
Expand Down Expand Up @@ -130,10 +132,8 @@ namespace hpp {
/// Test if a point is in the wanted range
bool filterPoint(uint32_t pointcloud_id, uint32_t row_id);

void attachOctreeToRobot
(const OcTreePtr_t& octree, const std::string& octreeFrame);
bool displayOctree(const OcTreePtr_t& octree,
const std::string& octreeFrame);
void attachOctreeToRobot(const std::string& octreeFrame);
bool displayOctree(const std::string& octreeFrame);
bool undisplayOctree(const std::string& octreeFrame);
ProblemSolverPtr_t problemSolver_;
bool waitingForData_;
Expand All @@ -142,6 +142,7 @@ namespace hpp {

// Vector of the different point clouds measured
std::vector<PointMatrix_t> pointsInSensorFrame_;
OcTreePtr_t octree_;
PointMatrix_t pointsInLinkFrame_;
value_type minDistance_, maxDistance_;
bool display_;
Expand Down
33 changes: 21 additions & 12 deletions src/point-cloud.cc
Original file line number Diff line number Diff line change
Expand Up @@ -123,9 +123,8 @@ namespace hpp {
movePointCloud(octreeFrame, sensorFrame, configuration);

// build octree
hpp::fcl::OcTreePtr_t octree(hpp::fcl::makeOctree(pointsInLinkFrame_,
resolution));
attachOctreeToRobot(octree, octreeFrame);
octree_ = hpp::fcl::makeOctree(pointsInLinkFrame_, resolution);
attachOctreeToRobot(octreeFrame);
return true;
}

Expand All @@ -149,7 +148,7 @@ namespace hpp {
// Remove point cloud from gepetto-gui.
undisplayOctree(octreeFrame);
}

octree_.reset();
}

void PointCloud::setDistanceBounds(value_type min, value_type max)
Expand All @@ -162,6 +161,17 @@ namespace hpp {
display_ = flag;
}

/// Refresh octree in gepetto-viewer
void PointCloud::refreshOctree()
{
if (octreeFrame_.empty()) return;
if (display_){
// Remove point cloud from gepetto-gui.
undisplayOctree(octreeFrame_);
displayOctree(octreeFrame_);
}
}

void checkFields(const std::vector<sensor_msgs::PointField>& fields)
{
// Check that number of fields is at least 3
Expand Down Expand Up @@ -260,7 +270,8 @@ namespace hpp {
}
}
ROS_INFO_STREAM("Used " << iPoint << " out of "
<< data->height * data->width " to build point cloud.")
<< data->height * data->width
<< " to build point cloud.");
pointsInSensorFrame_[pc_id].conservativeResize(iPoint, 3);
}

Expand Down Expand Up @@ -313,8 +324,7 @@ namespace hpp {
}
}

void PointCloud::attachOctreeToRobot
(const OcTreePtr_t& octree, const std::string& octreeFrame)
void PointCloud::attachOctreeToRobot(const std::string& octreeFrame)
{
const DevicePtr_t& robot (problemSolver_->robot());
const Frame& of(robot->getFrameByName(octreeFrame));
Expand All @@ -328,7 +338,7 @@ namespace hpp {
}
::pinocchio::GeometryObject octreeGo
(name,std::numeric_limits<FrameIndex>::max(), pinOctreeFrame.parent,
octree, Transform3f::Identity());
octree_, Transform3f::Identity());
GeomIndex octreeGeomId(robot->geomModel().addGeometryObject(octreeGo));
// Add collision pairs with all objects not attached to the octree joint.
for (std::size_t geomId=0; geomId <
Expand All @@ -351,22 +361,21 @@ namespace hpp {
problemSolver_->resetProblem();
if (display_){
// Display point cloud in gepetto-gui.
displayOctree(octree, octreeFrame);
displayOctree(octreeFrame);
}
}

#ifdef CLIENT_TO_GEPETTO_VIEWER

bool PointCloud::displayOctree
(const OcTreePtr_t& octree, const std::string& octreeFrame)
bool PointCloud::displayOctree(const std::string& octreeFrame)
{
std::string prefix("robot/");
// Connect to gepetto-gui without raising exception
gepetto::viewer::corba::connect(0x0, true);
gepetto::corbaserver::GraphicalInterface_var gui
(gepetto::viewer::corba::gui());
std::string nodeName(prefix + octreeFrame + std::string("/octree"));
octree->exportAsObjFile("/tmp/octree.obj");
octree_->exportAsObjFile("/tmp/octree.obj");
try {
// If node already exists, remove it
if (gui->nodeExists(nodeName.c_str())){
Expand Down

0 comments on commit 5110cfe

Please sign in to comment.