Skip to content

Commit e489b80

Browse files
committed
Release 0.8.4
1 parent b3642e5 commit e489b80

File tree

16 files changed

+172
-60
lines changed

16 files changed

+172
-60
lines changed

.travis.sh

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
#!/bin/bash
2+
3+
set -e
4+
5+
apt-get update && apt-get install -y -q wget sudo lsb-release # for docker
6+
7+
#before_install:
8+
sh -c "echo \"deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main\" > /etc/apt/sources.list.d/ros-latest.list"
9+
sh -c "echo \"deb http://realsense-alm-public.s3.amazonaws.com/apt-repo `lsb_release -sc` main\" > /etc/apt/sources.list.d/realsense-latest.list"
10+
wget http://packages.ros.org/ros.key -O - | apt-key add -
11+
apt-key adv --keyserver keys.gnupg.net --recv-key D6FB2970
12+
apt-get update
13+
apt-get install -y python-catkin-pkg python-rosdep python-wstool ros-kinetic-catkin librealsense-object-recognition-dev librealsense-persontracking-dev librealsense-slam-dev libopencv-dev
14+
source /opt/ros/$ROS_DISTRO/setup.bash
15+
rosdep init
16+
rosdep update
17+
18+
#install:
19+
mkdir -p ~/catkin_ws/src
20+
cd ~/catkin_ws/src
21+
catkin_init_workspace
22+
cd ~/catkin_ws
23+
catkin_make
24+
source devel/setup.bash
25+
cd ~/catkin_ws/src
26+
ln -s $CI_SOURCE_PATH .
27+
28+
#before_script:
29+
cd ~/catkin_ws
30+
rosdep install -q -y -r --from-paths src --ignore-src --rosdistro $ROS_DISTRO
31+
32+
#script:
33+
source /opt/ros/$ROS_DISTRO/setup.bash
34+
cd ~/catkin_ws
35+
catkin_make

.travis.yml

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
sudo: required
2+
dist: trusty
3+
language: generic
4+
5+
env:
6+
- ROS_DISTRO=kinetic
7+
8+
before_install:
9+
- export CI_SOURCE_PATH=$(pwd)
10+
- export REPOSITORY_NAME=${PWD##*/}
11+
12+
script:
13+
- echo "Testing branch $TRAVIS_BRANCH of $REPOSITORY_NAME"
14+
- docker run --rm -i -v $CI_SOURCE_PATH:$CI_SOURCE_PATH -e "CI_SOURCE_PATH=$CI_SOURCE_PATH" -e "HOME=$HOME" -e "ROS_DISTRO=$ROS_DISTRO" -t ubuntu:xenial sh -c "cd $CI_SOURCE_PATH; ./.travis.sh"
15+

realsense_ros_camera/CHANGELOG.rst

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,12 @@
22
Changelog for package realsense_ros_camera
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.8.4 (2017-04-28)
6+
------------------
7+
* Fixed broken dependencies in packages, causing rosdep to fail when building on clean machine
8+
* ROS timestamp fixes
9+
* Contributors: Matt Curfman
10+
511
0.8.3 (2017-04-21)
612
------------------
713
* Added URDF models for R200 and ZR300 cameras

realsense_ros_camera/package.xml

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package>
33
<name>realsense_ros_camera</name>
4-
<version>0.8.3</version>
4+
<version>0.8.4</version>
55
<description>The realsense_ros_camera package</description>
66
<maintainer email="[email protected]">Intel RealSense</maintainer>
77
<license>Apache 2.0</license>
@@ -15,6 +15,7 @@
1515
<build_depend>cv_bridge</build_depend>
1616
<build_depend>image_transport</build_depend>
1717
<build_depend>tf</build_depend>
18+
<build_depend>camera_info_manager</build_depend>
1819
<run_depend>image_transport</run_depend>
1920
<run_depend>cv_bridge</run_depend>
2021
<run_depend>nodelet</run_depend>
@@ -24,6 +25,7 @@
2425
<run_depend>std_msgs</run_depend>
2526
<run_depend>message_runtime</run_depend>
2627
<run_depend>tf</run_depend>
28+
<run_depend>camera_info_manager</run_depend>
2729
<export>
2830
<nodelet plugin="${prefix}/nodelet_plugins.xml" />
2931
</export>

realsense_ros_camera/src/camera_node.cpp

Lines changed: 37 additions & 35 deletions
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,8 @@ class NodeletCamera: public nodelet::Nodelet
3535
{
3636
public:
3737
NodeletCamera() :
38-
cameraStarted_(false)
38+
cameraStarted_(false),
39+
intialize_time_base_(false)
3940
{
4041
// Types for depth stream
4142
format_[rs::stream::depth] = rs::format::z16; // libRS type
@@ -209,11 +210,6 @@ class NodeletCamera: public nodelet::Nodelet
209210
info_publisher_[rs::stream::fisheye] =
210211
node_handle.advertise< sensor_msgs::CameraInfo >("camera/fisheye/camera_info", 1);
211212

212-
// HW timestamp version of image publishers, for realsense_ros_slam package
213-
image_publishers_hw_timestamp_[rs::stream::color] = node_handle.advertise<sensor_msgs::Image>("/camera/color/image_raw_hw_timestamp", 1);
214-
image_publishers_hw_timestamp_[rs::stream::depth] = node_handle.advertise<sensor_msgs::Image>("/camera/depth/image_raw_hw_timestamp", 1);
215-
image_publishers_hw_timestamp_[rs::stream::fisheye] = node_handle.advertise<sensor_msgs::Image>("/camera/fisheye/image_raw_hw_timestamp", 1);
216-
217213
imu_publishers_[RS_EVENT_IMU_GYRO] = node_handle.advertise< sensor_msgs::Imu >("camera/gyro/sample", 100);
218214
imu_publishers_[RS_EVENT_IMU_ACCEL] = node_handle.advertise< sensor_msgs::Imu >("camera/accel/sample", 100);
219215

@@ -240,14 +236,33 @@ class NodeletCamera: public nodelet::Nodelet
240236
stream_callback_per_stream[stream] = [this,stream](rs::frame frame)
241237
{
242238
image_[stream].data = (unsigned char *) frame.get_data();
243-
ros::Time t = ros::Time::now();
239+
240+
if ((true == isZR300_) && (rs::timestamp_domain::microcontroller != frame.get_frame_timestamp_domain()))
241+
{
242+
ROS_ERROR_STREAM("error: Junk time stamp in stream:" << (int)(stream) <<
243+
"\twith frame counter:" << frame.get_frame_number());
244+
return;
245+
}
246+
247+
// We compute a ROS timestamp which is based on an initial ROS time at point of first frame,
248+
// and the incremental timestamp from the camera.
249+
if(false == intialize_time_base_)
250+
{
251+
intialize_time_base_ = true;
252+
ros_time_base_ = ros::Time::now();
253+
camera_time_base_ = frame.get_timestamp();
254+
}
255+
double elapsed_camera_ms = (/*ms*/ frame.get_timestamp() - /*ms*/ camera_time_base_) / /*ms to seconds*/ 1000;
256+
ros::Time t(ros_time_base_.toSec() + elapsed_camera_ms);
244257

258+
// If this stream is associated with depth and we have at least one point cloud subscriber,
259+
// service it here.
245260
if((stream == rs::stream::depth) && (0 != pointcloud_publisher_.getNumSubscribers()))
246261
publishPCTopic(t);
247262

248-
seq_[stream] += 1;
249-
if((0 != image_publishers_[stream].getNumSubscribers()) ||
250-
(0 != image_publishers_hw_timestamp_[stream].getNumSubscribers()))
263+
seq_[stream] += 1;
264+
if((0 != info_publisher_[stream].getNumSubscribers()) ||
265+
(0 != image_publishers_[stream].getNumSubscribers()))
251266
{
252267
sensor_msgs::ImagePtr img;
253268
img = cv_bridge::CvImage(std_msgs::Header(), encoding_[stream], image_[stream]).toImageMsg();
@@ -259,28 +274,8 @@ class NodeletCamera: public nodelet::Nodelet
259274
img->header.stamp = t;
260275
img->header.seq = seq_[stream];
261276

262-
// ROS Timestamp
263-
if(0 != image_publishers_[stream].getNumSubscribers())
264-
image_publishers_[stream].publish(img);
265-
266-
// Camera HW Timestamp for realsense_ros_slam
267-
if(0 != image_publishers_hw_timestamp_[stream].getNumSubscribers())
268-
{
269-
if (rs::timestamp_domain::microcontroller != frame.get_frame_timestamp_domain())
270-
{
271-
ROS_ERROR_STREAM("error: Junk time stamp in stream:" << (int)(stream) <<
272-
"\twith frame counter:" << frame.get_frame_number());
273-
}
274-
else
275-
{
276-
img->header.stamp = ros::Time(frame.get_timestamp());
277-
image_publishers_hw_timestamp_[stream].publish(img);
278-
}
279-
}
280-
}
281-
282-
if(0 != image_publishers_[stream].getNumSubscribers())
283-
{
277+
image_publishers_[stream].publish(img);
278+
284279
camera_info_[stream].header.stamp = t;
285280
camera_info_[stream].header.seq = seq_[stream];
286281
info_publisher_[stream].publish(camera_info_[stream]);
@@ -307,6 +302,7 @@ class NodeletCamera: public nodelet::Nodelet
307302
{
308303
// Needed to align image timestamps to common clock-domain with the motion events
309304
device_->set_option(rs::option::fisheye_strobe, 1);
305+
310306
// This option causes the fisheye image to be aquired in-sync with the depth image.
311307
device_->set_option(rs::option::fisheye_external_trigger, 1);
312308
device_->set_option(rs::option::fisheye_color_auto_exposure, 1);
@@ -328,8 +324,12 @@ class NodeletCamera: public nodelet::Nodelet
328324
if( 0 == imu_publishers_[motionType].getNumSubscribers())
329325
return;
330326

327+
if(false == intialize_time_base_)
328+
return;
329+
double elapsed_camera_ms = (/*ms*/ entry.timestamp_data.timestamp - /*ms*/ camera_time_base_) / /*ms to seconds*/ 1000;
330+
ros::Time t(ros_time_base_.toSec() + elapsed_camera_ms);
331+
331332
sensor_msgs::Imu imu_msg = sensor_msgs::Imu();
332-
imu_msg.header.stamp = ros::Time::now();
333333
imu_msg.header.frame_id = optical_imu_id_[motionType];
334334
imu_msg.orientation.x = 0.0;
335335
imu_msg.orientation.y = 0.0;
@@ -350,7 +350,7 @@ class NodeletCamera: public nodelet::Nodelet
350350
}
351351
seq_motion[motionType] += 1;
352352
imu_msg.header.seq = seq_motion[motionType];
353-
imu_msg.header.stamp = ros::Time(entry.timestamp_data.timestamp);
353+
imu_msg.header.stamp = t;
354354
imu_publishers_[motionType].publish(imu_msg);
355355
};
356356

@@ -703,7 +703,6 @@ class NodeletCamera: public nodelet::Nodelet
703703

704704
// R200 and ZR300 types
705705
std::map<rs::stream, image_transport::Publisher> image_publishers_;
706-
std::map<rs::stream, ros::Publisher> image_publishers_hw_timestamp_;
707706
std::map<rs::stream, int> image_format_;
708707
std::map<rs::stream, rs::format> format_;
709708
std::map<rs::stream, ros::Publisher> info_publisher_;
@@ -718,6 +717,9 @@ class NodeletCamera: public nodelet::Nodelet
718717
std::map<rs::stream, std::function<void(rs::frame)>> stream_callback_per_stream;
719718
std::map<rs::stream, sensor_msgs::CameraInfo> camera_info_;
720719
ros::Publisher pointcloud_publisher_;
720+
bool intialize_time_base_;
721+
double camera_time_base_;
722+
ros::Time ros_time_base_;
721723

722724
// ZR300 specific types
723725
bool isZR300_ = false;

realsense_ros_object/CHANGELOG.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22
Changelog for package realsense_ros_object
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.8.4 (2017-04-28)
6+
------------------
7+
58
0.8.3 (2017-04-21)
69
------------------
710

realsense_ros_object/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package>
33
<name>realsense_ros_object</name>
4-
<version>0.8.3</version>
4+
<version>0.8.4</version>
55
<description>The realsense_ros_object package</description>
66
<maintainer email="[email protected]">Intel RealSense</maintainer>
77
<license>Apache 2.0</license>

realsense_ros_person/CHANGELOG.rst

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,11 @@
22
Changelog for package realsense_ros_person
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.8.4 (2017-04-28)
6+
------------------
7+
* Fixed broken dependencies in packages, causing rosdep to fail when building on clean machine
8+
* Contributors: Matt Curfman
9+
510
0.8.3 (2017-04-21)
611
------------------
712
* Added instructions for record/playback

realsense_ros_person/package.xml

Lines changed: 2 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package>
33
<name>realsense_ros_person</name>
4-
<version>0.8.3</version>
4+
<version>0.8.4</version>
55
<description>The realsense_ros_person package</description>
66
<maintainer email="[email protected]">Intel RealSense</maintainer>
77
<license>Apache 2.0</license>
@@ -17,8 +17,6 @@
1717
<build_depend>roscpp_serialization</build_depend>
1818
<build_depend>rospy</build_depend>
1919
<build_depend>sensor_msgs</build_depend>
20-
<build_depend>realsense_msgs</build_depend>
21-
<build_depend>realsense_srvs</build_depend>
2220
<run_depend>cv_bridge</run_depend>
2321
<run_depend>image_transport</run_depend>
2422
<run_depend>message_filters</run_depend>
@@ -27,7 +25,7 @@
2725
<run_depend>roscpp</run_depend>
2826
<run_depend>std_msgs</run_depend>
2927
<run_depend>rostime</run_depend>
30-
<run_depend>realsense_camera</run_depend>
28+
<run_depend>realsense_ros_camera</run_depend>
3129
<run_depend>roscpp_serialization</run_depend>
3230
<run_depend>rospy</run_depend>
3331
<run_depend>sensor_msgs</run_depend>

realsense_ros_slam/CHANGELOG.rst

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,13 @@
22
Changelog for package realsense_ros_slam
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
0.8.4 (2017-04-28)
6+
------------------
7+
* Fixed broken dependencies in packages, causing rosdep to fail when building on clean machine
8+
* ROS timestamp fixes
9+
* Added launch arguments for loading of occupancy map and relocalization map.
10+
* Contributors: Ben Hirashima, Matt Curfman
11+
512
0.8.3 (2017-04-21)
613
------------------
714
* Added a service to save slam output to files.

0 commit comments

Comments
 (0)