uzh-rpg / flightmare

An Open Flexible Quadrotor Simulator
https://uzh-rpg.github.io/flightmare/
Other
1.03k stars 346 forks source link

increase camera frame rates #82

Open Sebastien-Rob opened 3 years ago

Sebastien-Rob commented 3 years ago

Hi, When i run camera node, i have just 8 frame per second and code below 4 frame per second for rgb topic and others images topics. How i can up this ? Thanks.

void FlightPilot::mainLoopCallback(const ros::TimerEvent &event) {

    quad_ptr_->setState(quad_state_);
    //std::cout << quad_state_.x[QS::POSX] << std::endl; //debug

    unity_bridge_ptr_->getRender(frame_id);
    unity_bridge_ptr_->handleOutput();

    cv::Mat img;

    ros::Time timestamp = ros::Time::now();

    rgb_camera_->getRGBImage(img);
    sensor_msgs::ImagePtr rgb_msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", img).toImageMsg();
    rgb_msg->header.stamp = timestamp;
    rgb_msg->header.frame_id = "camera";
    rgb_pub.publish(rgb_msg);

    rgb_camera_->getDepthMap(img);
    sensor_msgs::ImagePtr depth_msg = cv_bridge::CvImage(std_msgs::Header(), "32FC1", img).toImageMsg();
    depth_msg->header.stamp = timestamp;
    depth_msg->header.frame_id = "camera";
    depth_pub.publish(depth_msg);

    // Publishing camera calibration information
    camera_info_msg.header.stamp = ros::Time::now();
    cinfo_pub.publish(camera_info_msg);

    frame_id += 1;

}
yun-long commented 3 years ago

Hi, Sebastien, this is very odd. We have tested it on our PC and the frame rate is much higher than the number you report. What you can do is

Sebastien-Rob commented 3 years ago

Hi yun-long,

I want to keep a resolution of 480p and just get RGB and depth images. I had a frame rate of 7Hz. When i disable depth and optical flow, i up to 13Hz (if i disable all post processing i up to 27Hz) Finally, enable depth post processing + publish RGB + publish depth + run unity in a batch mode, i up to 17Hz.

It's much better thanks, You think it's possible to increase up to 30Hz for both ? (maybe others post processing for depth)

Thank you for help, nice work !

1216621137 commented 3 years ago

@Sebastien-Rob
Hello I have the same question. But I have changed mode into batchmode, it doesn't work. I have run these in three terminal:

  1. rosrun flightros camera
  2. ./RPG_Flightmare.x86 -batchmode(on the right folder)
  3. rosrun rviz rviz

Then, I run "rostopic hz /rgb" on another terminal. It shows the frame rate is still 8Hz. I don't know which step is wrong. Could you help me ? Thanks!!

Nunzio03 commented 1 year ago

Hi, Sebastien, this is very odd. We have tested it on our PC and the frame rate is much higher than the number you report. What you can do is

Hi @yun-long, I would like to ask:

I've tested on multiple computers with nvidia GPU enabled on Docker and by disabling depth, segmentation and optical flow i can barely reach 20 FPS (i'm checking with rostopic hz /rgb)