introlab / find-object

Find-Object project
http://introlab.github.io/find-object/
BSD 3-Clause "New" or "Revised" License
447 stars 189 forks source link

3D object #23

Open Nicolaschile opened 8 years ago

Nicolaschile commented 8 years ago

Hello, im Nicolas from chile. I am using your rtabslam and find_object projects. Everything works perfect, thank you very much for your work. the issue is that I'm trying to simulate the 3D tf position with another model of recognition. I'm really new programming ros and I'm no good at this time, so I was wondering if it is possible to maintain the position obtained with find_object_3D.launch and RTAB with rviz.

The purpose of this is to take your model to another model of recognition of people and then to other projects for the future. I'm currently using a package with HOG for recognition of heads which will add 3D positioning maintained over time to be displayed in rviz.

thanks,

matlabbe commented 8 years ago

Hi Nicolas,

By maintaining objects in RVIZ, do you mean that when the robot is not seeing anymore a detected object, the position of the object can be still visualized in RVIZ?

In the current find_object_3d demo, TF is shown on the detected object, but disappears when the camera is not detecting it anymore. A fast way to keep them in RVIZ would be to publish a Marker at these positions. Subscribe to objectsStamped, get the pose from TF, then publish markers. The markers in RVIZ don't disappear when not published anymore. However, if the map is optimized, the markers will not move at the corrected position.

Another solution is to create a node to save the position of a detected object accordingly to the current graph (MapGraph). Then keep in cache the transformation between the latest node in the graph and the position of the object. When the map is corrected, you can then move back the object position accordingly to the new corresponding pose in the graph.

cheers

Nicolaschile commented 8 years ago

hi, thanks Is precisely what I meant. for a matter of time I will use the first option for now. I was watching the tf_example.cpp file and is susbcribe to the topic find_object_2d/objectStamped, also the position is obtained.

ROSINFO("Object%d [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]", id, mapFrameId_.c_str(), pose.getOrigin().x(), pose.getOrigin().y(), pose.getOrigin().z(), pose.getRotation().x(), pose.getRotation().y(), pose.getRotation().z(), pose.getRotation().w()); ROSINFO("Object%d [x,y,z] [x,y,z,w] in \"%s\" frame: [%f,%f,%f] [%f,%f,%f,%f]", id, msg->header.frame_id.c_str(), poseCam.getOrigin().x(), poseCam.getOrigin().y(), poseCam.getOrigin().z(), poseCam.getRotation().x(), poseCam.getRotation().y(), poseCam.getRotation().z(), poseCam.getRotation().w());

if understand correctly, in this part are obtained the final position of the object. therefore should take these values and published whit the markers in the same file tf_example.cpp?

currently i studying tutorials/tf and trying to understand your work. tf_example.cpp obtain find_object.cpp values that are published in parallel with rtabslam? sorry if I take advantage of this but I'm trying to understand the issue well.

matlabbe commented 8 years ago

Yes, you could modify tf_example_node.cpp to publish markers using the pose position in /map frame.

Find-Object publishes objects detected in /camera frame. TF is used to transform that position in /map frame. RTAB-Map and Find-Object are working in parallel.

Nicolaschile commented 8 years ago

hi matt, I was wondering if you could keep helping me. create a new package with a file with "marks"

#include <ros/ros.h>
#include <visualization_msgs/Marker.h>

int main( int argc, char** argv )
{
  ros::init(argc, argv, "prueba1");
  ros::NodeHandle n;
  ros::Rate r(1);
  ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 1);

  uint32_t shape = visualization_msgs::Marker::CUBE;

  while (ros::ok())
  {
    visualization_msgs::Marker marker;
    marker.header.frame_id = "/map";
    marker.header.stamp = ros::Time::now();
    marker.ns = "basic_shapes";
    marker.id = 2;
    marker.type = shape;
    marker.action = visualization_msgs::Marker::ADD;
    marker.pose.position.x = 0;
    marker.pose.position.y = 0;
    marker.pose.position.z = 0;
    marker.pose.orientation.x = 0.0;
    marker.pose.orientation.y = 0.0;
    marker.pose.orientation.z = 0.0;
    marker.pose.orientation.w = 1.0;
    marker.scale.x = 0.3;
    marker.scale.y = 0.3;
    marker.scale.z = 0.3;
    marker.color.r = 0.0f;
    marker.color.g = 1.0f;
    marker.color.b = 0.0f;
    marker.color.a = 1.0;
    marker.lifetime = ros::Duration();

    while (marker_pub.getNumSubscribers() < 1)
    {
      if (!ros::ok())
      {
        return 0;
      }
      ROS_WARN_ONCE("Please create a subscriber to the marker");
      sleep(1);
    }
    marker_pub.publish(marker);
    r.sleep();
  }
}

but really do not know how to unite the topics published by find_object with the new package, you could help me, if it's not too much trouble claro, ya has sido de gran ayuda gracias.

maybe it's better to modify the file tf_example.cpp instead of creating a new package. creating new dependencies needed to find_object

matlabbe commented 8 years ago

You could copy tf_example_node.cpp in your package. The ros dependencies of your package would be tf and find_object_2d.

cheers

Nicolaschile commented 8 years ago

thanks mat. I had already tried to do this but I had a problem with that and I was not able to solve.

fatal error: QtCore/QString: No existe el archivo o el directorio

include <QtCore/QString>

sorry, im noob here.

adding
find_package(Qt5Widgets REQUIRED) find_package(Qt5Core REQUIRED) dependency on Cmakelist dont work

matlabbe commented 8 years ago

You don't really need Qt to make it work, you can remove the header and change that line to not use Qt.

Nicolaschile commented 8 years ago

also try that but this line gives me an error (QString); I'm looking how replace this but still do not get any good result

// get data
int id = (int)msg->objects.data[i];
std::string objectFrameId = QString("%1_%2").arg(objFramePrefix_.c_str()).arg(id).toStdString(); // "object_1", "object_2"

sorry I had not seen the link. That's right, I'm struggling with that haha

can you helpe whit this line


ros::NodeHandle pnh("~");
pnh.param("map_frame_id", mapFrameId_, mapFrameId_);
pnh.param("object_prefix", objFramePrefix_, objFramePrefix_);

i know you start the node, but i do not understand "pnh", are the variables containing and parameters?