Skip to content

Commit

Permalink
issue ros-simulation#408 this should fix the timestamp to the time th…
Browse files Browse the repository at this point in the history
…e most recent image was acquired in the sim.

Haven't tested because getting:

    unsupported pickle protocol: 4
    log4cxx: Could not read configuration file [/home/lucasw/.ros/rosconsole.config].
    log4cxx: Could not read configuration file [/home/lucasw/.ros/rosconsole.config].
    [urdf_spawner-3] process has died [pid 30719, exit code 1, cmd /home/lucasw/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros/scripts/spawn_model -urdf -model rrbot -param robot_description __name:=urdf_spawner __log:=/home/lucasw/.ros/log/f00e5c50-ec35-11e5-98b1-00dbdf11ceac/urdf_spawner-3.log].
    log file: /home/lucasw/.ros/log/f00e5c50-ec35-11e5-98b1-00dbdf11ceac/urdf_spawner-3*.log

when trying to run rrbot_gazebo.  gazebo by itself seems to launch though.
  • Loading branch information
lucasw committed Mar 18, 2016
1 parent c190bf6 commit a8267ee
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions gazebo_plugins/src/gazebo_ros_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ void GazeboRosCamera::OnNewFrame(const unsigned char *_image,
unsigned int _width, unsigned int _height, unsigned int _depth,
const std::string &_format)
{
this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
common::Time sensor_update_time = this->parentSensor_->GetLastUpdateTime();

if (!this->parentSensor->IsActive())
{
Expand All @@ -91,8 +91,8 @@ void GazeboRosCamera::OnNewFrame(const unsigned char *_image,
common::Time cur_time = this->world_->GetSimTime();
if (cur_time - this->last_update_time_ >= this->update_period_)
{
this->PutCameraData(_image);
this->PublishCameraInfo();
this->PutCameraData(_image, sensor_update_time);
this->PublishCameraInfo(sensor_update_time);
this->last_update_time_ = cur_time;
}
}
Expand Down

0 comments on commit a8267ee

Please sign in to comment.