Skip to content

Commit

Permalink
Merge pull request #2790 from dorodnic/community_fixes
Browse files Browse the repository at this point in the history
Community fixes
  • Loading branch information
dorodnic authored Nov 29, 2018
2 parents 8631ce4 + b802c1f commit a7fc189
Show file tree
Hide file tree
Showing 169 changed files with 1,152 additions and 1,154 deletions.
16 changes: 8 additions & 8 deletions examples/example.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -381,27 +381,27 @@ class window
glfwMakeContextCurrent(win);

glfwSetWindowUserPointer(win, this);
glfwSetMouseButtonCallback(win, [](GLFWwindow * win, int button, int action, int mods)
glfwSetMouseButtonCallback(win, [](GLFWwindow * w, int button, int action, int mods)
{
auto s = (window*)glfwGetWindowUserPointer(win);
auto s = (window*)glfwGetWindowUserPointer(w);
if (button == 0) s->on_left_mouse(action == GLFW_PRESS);
});

glfwSetScrollCallback(win, [](GLFWwindow * win, double xoffset, double yoffset)
glfwSetScrollCallback(win, [](GLFWwindow * w, double xoffset, double yoffset)
{
auto s = (window*)glfwGetWindowUserPointer(win);
auto s = (window*)glfwGetWindowUserPointer(w);
s->on_mouse_scroll(xoffset, yoffset);
});

glfwSetCursorPosCallback(win, [](GLFWwindow * win, double x, double y)
glfwSetCursorPosCallback(win, [](GLFWwindow * w, double x, double y)
{
auto s = (window*)glfwGetWindowUserPointer(win);
auto s = (window*)glfwGetWindowUserPointer(w);
s->on_mouse_move(x, y);
});

glfwSetKeyCallback(win, [](GLFWwindow * win, int key, int scancode, int action, int mods)
glfwSetKeyCallback(win, [](GLFWwindow * w, int key, int scancode, int action, int mods)
{
auto s = (window*)glfwGetWindowUserPointer(win);
auto s = (window*)glfwGetWindowUserPointer(w);
if (0 == action) // on key release
{
s->on_key_release(key);
Expand Down
26 changes: 13 additions & 13 deletions examples/measure/rs-measure.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,16 +30,16 @@ float dist_2d(const pixel& a, const pixel& b);
struct toggle
{
toggle() : x(0.f), y(0.f) {}
toggle(float x, float y)
: x(std::min(std::max(x, 0.f), 1.f)),
y(std::min(std::max(y, 0.f), 1.f))
toggle(float xl, float yl)
: x(std::min(std::max(xl, 0.f), 1.f)),
y(std::min(std::max(yl, 0.f), 1.f))
{}

// Move from [0,1] space to pixel space of specific frame
pixel get_pixel(rs2::depth_frame frame) const
pixel get_pixel(rs2::depth_frame frm) const
{
int px = x * frame.get_width();
int py = y * frame.get_height();
int px = x * frm.get_width();
int py = y * frm.get_height();
return{ px, py };
}

Expand Down Expand Up @@ -287,16 +287,16 @@ int main(int argc, char * argv[]) try
// Calculate distance in 3D between the two neighboring pixels
auto d = dist_3d(depth, u, v);
// Calculate total distance from source
auto total_dist = dist[u] + d;
auto total_distl = dist[u] + d;

// If we encounter a potential improvement,
if (dist[v] > total_dist)
if (dist[v] > total_distl)
{
// Update parent and distance
parent[v] = u;
dist[v] = total_dist;
dist[v] = total_distl;
// And re-visit that pixel by re-introducing it to the queue
q.emplace(total_dist, v);
q.emplace(total_distl, v);
}
}
}
Expand Down Expand Up @@ -496,9 +496,9 @@ void render_shortest_path(const rs2::depth_frame& depth,

for (int i = 0; i < path.size(); i++)
{
auto&& pixel = path[i];
auto x = (float(pixel.first) / depth.get_width()) * app.width();
auto y = (float(pixel.second) / depth.get_height()) * app.height();
auto&& pixel1 = path[i];
auto x = (float(pixel1.first) / depth.get_width()) * app.width();
auto y = (float(pixel1.second) / depth.get_height()) * app.height();
glVertex2f(x, y);

if (i == path.size() / 2) center = { x, y };
Expand Down
10 changes: 5 additions & 5 deletions examples/post-processing/rs-post-processing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -348,9 +348,9 @@ bool filter_slider_ui::is_all_integers(const rs2::option_range& range)
/**
Constructor for filter_options, takes a name and a filter.
*/
filter_options::filter_options(const std::string name, rs2::filter& filter) :
filter_options::filter_options(const std::string name, rs2::filter& flt) :
filter_name(name),
filter(filter),
filter(flt),
is_enabled(true)
{
const std::array<rs2_option, 3> possible_filter_options = {
Expand All @@ -362,13 +362,13 @@ filter_options::filter_options(const std::string name, rs2::filter& filter) :
//Go over each filter option and create a slider for it
for (rs2_option opt : possible_filter_options)
{
if (filter.supports(opt))
if (flt.supports(opt))
{
rs2::option_range range = filter.get_option_range(opt);
rs2::option_range range = flt.get_option_range(opt);
supported_options[opt].range = range;
supported_options[opt].value = range.def;
supported_options[opt].is_int = filter_slider_ui::is_all_integers(range);
supported_options[opt].description = filter.get_option_description(opt);
supported_options[opt].description = flt.get_option_description(opt);
std::string opt_name = rs2_option_to_string(opt);
supported_options[opt].name = name + "_" + opt_name;
std::string prefix = "Filter ";
Expand Down
28 changes: 13 additions & 15 deletions include/librealsense2/hpp/rs_frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -304,16 +304,16 @@ namespace rs2
* Base class for multiple frame extensions with internal frame handle
* \param[in] rs2_frame frame_ref - internal frame instance
*/
frame(rs2_frame* frame_ref) : frame_ref(frame_ref)
frame(rs2_frame* ref) : frame_ref(ref)
{
#ifdef _DEBUG
if (frame_ref)
if (ref)
{
rs2_error* e = nullptr;
auto r = rs2_get_frame_number(frame_ref, &e);
auto r = rs2_get_frame_number(ref, &e);
if (!e)
frame_number = r;
auto s = rs2_get_frame_stream_profile(frame_ref, &e);
auto s = rs2_get_frame_stream_profile(ref, &e);
if (!e)
profile = stream_profile(s);
}
Expand Down Expand Up @@ -656,7 +656,6 @@ namespace rs2

if (get())
{
rs2_error* e = nullptr;
_size = rs2_get_frame_points_count(get(), &e);
error::handle(e);
}
Expand Down Expand Up @@ -853,7 +852,6 @@ namespace rs2

if (get())
{
rs2_error* e = nullptr;
_size = rs2_embedded_frames_count(get(), &e);
error::handle(e);
}
Expand All @@ -868,10 +866,10 @@ namespace rs2
frame first_or_default(rs2_stream s, rs2_format f = RS2_FORMAT_ANY) const
{
frame result;
foreach([&result, s, f](frame frame) {
if (!result && frame.get_profile().stream_type() == s && (f == RS2_FORMAT_ANY || f == frame.get_profile().format()))
foreach([&result, s, f](frame frm) {
if (!result && frm.get_profile().stream_type() == s && (f == RS2_FORMAT_ANY || f == frm.get_profile().format()))
{
result = std::move(frame);
result = std::move(frm);
}
});
return result;
Expand All @@ -884,9 +882,9 @@ namespace rs2
*/
frame first(rs2_stream s, rs2_format f = RS2_FORMAT_ANY) const
{
auto frame = first_or_default(s, f);
if (!frame) throw error("Frame of requested stream type was not found!");
return frame;
auto frm = first_or_default(s, f);
if (!frm) throw error("Frame of requested stream type was not found!");
return frm;
}

/**
Expand Down Expand Up @@ -928,9 +926,9 @@ namespace rs2
}
else
{
foreach([&f, index](const frame& frame) {
if (frame.get_profile().stream_type() == RS2_STREAM_INFRARED && frame.get_profile().stream_index() == index)
f = frame;
foreach([&f, index](const frame& frm) {
if (frm.get_profile().stream_type() == RS2_STREAM_INFRARED &&
frm.get_profile().stream_index() == index) f = frm;
});
}
return f;
Expand Down
2 changes: 1 addition & 1 deletion include/librealsense2/hpp/rs_pipeline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,7 +320,7 @@ namespace rs2
return _config;
}

config(std::shared_ptr<rs2_config> config) : _config(config) {}
config(std::shared_ptr<rs2_config> cfg) : _config(cfg) {}
private:
std::shared_ptr<rs2_config> _config;
};
Expand Down
8 changes: 4 additions & 4 deletions include/librealsense2/hpp/rs_record_playback.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -210,11 +210,11 @@ namespace rs2
* \param[in] file The desired path to which the recorder should save the data
* \param[in] device The device to record
*/
recorder(const std::string& file, rs2::device device)
recorder(const std::string& file, rs2::device dev)
{
rs2_error* e = nullptr;
_dev = std::shared_ptr<rs2_device>(
rs2_create_record_device(device.get().get(), file.c_str(), &e),
rs2_create_record_device(dev.get().get(), file.c_str(), &e),
rs2_delete_device);
rs2::error::handle(e);
}
Expand All @@ -225,11 +225,11 @@ namespace rs2
* \param[in] device The device to record
* \param[in] compression_enabled Indicates if compression is enabled
*/
recorder(const std::string& file, rs2::device device, bool compression_enabled)
recorder(const std::string& file, rs2::device dev, bool compression_enabled)
{
rs2_error* e = nullptr;
_dev = std::shared_ptr<rs2_device>(
rs2_create_record_device_ex(device.get().get(), file.c_str(), compression_enabled, &e),
rs2_create_record_device_ex(dev.get().get(), file.c_str(), compression_enabled, &e),
rs2_delete_device);
rs2::error::handle(e);
}
Expand Down
12 changes: 6 additions & 6 deletions include/librealsense2/hpp/rs_sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,18 +13,18 @@ namespace rs2
class notification
{
public:
notification(rs2_notification* notification)
notification(rs2_notification* nt)
{
rs2_error* e = nullptr;
_description = rs2_get_notification_description(notification, &e);
_description = rs2_get_notification_description(nt, &e);
error::handle(e);
_timestamp = rs2_get_notification_timestamp(notification, &e);
_timestamp = rs2_get_notification_timestamp(nt, &e);
error::handle(e);
_severity = rs2_get_notification_severity(notification, &e);
_severity = rs2_get_notification_severity(nt, &e);
error::handle(e);
_category = rs2_get_notification_category(notification, &e);
_category = rs2_get_notification_category(nt, &e);
error::handle(e);
_serialized_data = rs2_get_notification_serialized_data(notification, &e);
_serialized_data = rs2_get_notification_serialized_data(nt, &e);
error::handle(e);
}

Expand Down
4 changes: 2 additions & 2 deletions include/librealsense2/rs.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ extern "C" {
#include "h/rs_sensor.h"

#define RS2_API_MAJOR_VERSION 2
#define RS2_API_MINOR_VERSION 16
#define RS2_API_PATCH_VERSION 5
#define RS2_API_MINOR_VERSION 17
#define RS2_API_PATCH_VERSION 0
#define RS2_API_BUILD_VERSION 0

#define STRINGIFY(arg) #arg
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
<package format="2">
<name>librealsense2</name>
<!-- The version tag needs to be updated with each new release of librealsense -->
<version>2.16.5</version>
<version>2.17.0</version>
<description>
Library for capturing data from the Intel(R) RealSense(TM) SR300 and D400 cameras. This effort was initiated to better support researchers, creative coders, and app developers in domains such as robotics, virtual reality, and the internet of things. Several often-requested features of RealSense(TM); devices are implemented in this project, including multi-camera capture.
</description>
Expand Down
10 changes: 5 additions & 5 deletions src/media/ros/ros_file_format.h
Original file line number Diff line number Diff line change
Expand Up @@ -533,21 +533,21 @@ namespace librealsense
return device_serializer::nanoseconds::min();
}

inline device_serializer::nanoseconds to_nanoseconds(const ros::Time& t)
inline device_serializer::nanoseconds to_nanoseconds(const rs2rosinternal::Time& t)
{
if (t == ros::TIME_MIN)
if (t == rs2rosinternal::TIME_MIN)
return get_static_file_info_timestamp();

return device_serializer::nanoseconds(t.toNSec());
}

inline ros::Time to_rostime(const device_serializer::nanoseconds& t)
inline rs2rosinternal::Time to_rostime(const device_serializer::nanoseconds& t)
{
if (t == get_static_file_info_timestamp())
return ros::TIME_MIN;
return rs2rosinternal::TIME_MIN;

auto secs = std::chrono::duration_cast<std::chrono::duration<double>>(t);
return ros::Time(secs.count());
return rs2rosinternal::Time(secs.count());
}

namespace legacy_file_format
Expand Down
14 changes: 7 additions & 7 deletions src/media/ros/ros_reader.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ namespace librealsense
throw invalid_value_exception(to_string() << "Requested time is out of playback length. (Requested = " << seek_time.count() << ", Duration = " << m_total_duration.count() << ")");
}
auto seek_time_as_secs = std::chrono::duration_cast<std::chrono::duration<double>>(seek_time);
auto seek_time_as_rostime = ros::Time(seek_time_as_secs.count());
auto seek_time_as_rostime = rs2rosinternal::Time(seek_time_as_secs.count());

m_samples_view.reset(new rosbag::View(m_file, FalseQuery()));

Expand All @@ -119,7 +119,7 @@ namespace librealsense
{
view.addQuery(m_file, rosbag::TopicQuery(topic), start_time, as_rostime);
}
std::map<device_serializer::stream_identifier, ros::Time> last_frames;
std::map<device_serializer::stream_identifier, rs2rosinternal::Time> last_frames;
for (auto&& m : view)
{
if (m.isType<sensor_msgs::Image>() || m.isType<sensor_msgs::Imu>())
Expand Down Expand Up @@ -156,7 +156,7 @@ namespace librealsense

virtual void enable_stream(const std::vector<device_serializer::stream_identifier>& stream_ids) override
{
ros::Time start_time = ros::TIME_MIN + ros::Duration{ 0, 1 }; //first non 0 timestamp and afterward
rs2rosinternal::Time start_time = rs2rosinternal::TIME_MIN + rs2rosinternal::Duration{ 0, 1 }; //first non 0 timestamp and afterward
if (m_samples_view == nullptr) //Starting to stream
{
m_samples_view = std::unique_ptr<rosbag::View>(new rosbag::View(m_file, FalseQuery()));
Expand Down Expand Up @@ -204,7 +204,7 @@ namespace librealsense
{
return;
}
ros::Time curr_time;
rs2rosinternal::Time curr_time;
if (m_samples_itrator == m_samples_view->end())
{
curr_time = m_samples_view->getEndTime();
Expand Down Expand Up @@ -248,7 +248,7 @@ namespace librealsense
{
throw io_exception(to_string()
<< "Invalid file format, expected "
<< ros::message_traits::DataType<ROS_TYPE>::value()
<< rs2rosinternal::message_traits::DataType<ROS_TYPE>::value()
<< " message but got: " << msg.getDataType()
<< "(Topic: " << msg.getTopic() << ")");
}
Expand Down Expand Up @@ -1038,8 +1038,8 @@ namespace librealsense
{
throw io_exception(to_string()
<< "Invalid file format, expected "
<< ros::message_traits::DataType<realsense_legacy_msgs::motion_stream_info>::value()
<< " or " << ros::message_traits::DataType<realsense_legacy_msgs::stream_info>::value()
<< rs2rosinternal::message_traits::DataType<realsense_legacy_msgs::motion_stream_info>::value()
<< " or " << rs2rosinternal::message_traits::DataType<realsense_legacy_msgs::stream_info>::value()
<< " message but got: " << infos_msg.getDataType()
<< "(Topic: " << infos_msg.getTopic() << ")");
}
Expand Down
6 changes: 3 additions & 3 deletions src/media/ros/ros_writer.h
Original file line number Diff line number Diff line change
Expand Up @@ -144,7 +144,7 @@ namespace librealsense
noti_msg.severity = get_string(n.severity);
noti_msg.description = n.description;
auto secs = std::chrono::duration_cast<std::chrono::duration<double>>(std::chrono::duration<double, std::nano>(n.timestamp));
noti_msg.timestamp = ros::Time(secs.count());
noti_msg.timestamp = rs2rosinternal::Time(secs.count());
noti_msg.serialized_data = n.serialized_data;
return noti_msg;
}
Expand Down Expand Up @@ -192,7 +192,7 @@ namespace librealsense
image.data.assign(p_data, p_data + size);
image.header.seq = static_cast<uint32_t>(vid_frame->get_frame_number());
std::chrono::duration<double, std::milli> timestamp_ms(vid_frame->get_frame_timestamp());
image.header.stamp = ros::Time(std::chrono::duration<double>(timestamp_ms).count());
image.header.stamp = rs2rosinternal::Time(std::chrono::duration<double>(timestamp_ms).count());
std::string TODO_CORRECT_ME = "0";
image.header.frame_id = TODO_CORRECT_ME;
auto image_topic = ros_topic::frame_data_topic(stream_id);
Expand All @@ -210,7 +210,7 @@ namespace librealsense

imu_msg.header.seq = static_cast<uint32_t>(frame.frame->get_frame_number());
std::chrono::duration<double, std::milli> timestamp_ms(frame.frame->get_frame_timestamp());
imu_msg.header.stamp = ros::Time(std::chrono::duration<double>(timestamp_ms).count());
imu_msg.header.stamp = rs2rosinternal::Time(std::chrono::duration<double>(timestamp_ms).count());
std::string TODO_CORRECT_ME = "0";
imu_msg.header.frame_id = TODO_CORRECT_ME;
auto data_ptr = reinterpret_cast<const float*>(frame.frame->get_frame_data());
Expand Down
Loading

0 comments on commit a7fc189

Please sign in to comment.