diff --git a/moveit_core/collision_detection/src/collision_octomap_filter.cpp b/moveit_core/collision_detection/src/collision_octomap_filter.cpp index 23a523aaf4..5256cb4891 100644 --- a/moveit_core/collision_detection/src/collision_octomap_filter.cpp +++ b/moveit_core/collision_detection/src/collision_octomap_filter.cpp @@ -98,13 +98,13 @@ int collision_detection::refineContactNormals(const World::ObjectConstPtr& objec continue; } - double cell_size = 0; if (!object->shapes_.empty()) { const shapes::ShapeConstPtr& shape = object->shapes_[0]; const std::shared_ptr shape_octree = std::dynamic_pointer_cast(shape); if (shape_octree) { + double cell_size = 0; std::shared_ptr octree = shape_octree->octree; cell_size = octree->getResolution(); for (auto& contact_info : contact_vector) @@ -174,7 +174,6 @@ bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const doub const double& r_multiple, const octomath::Vector3& contact_point, octomath::Vector3& normal, double& depth, const bool estimate_depth) { - double intensity; if (estimate_depth) { octomath::Vector3 surface_point; @@ -191,6 +190,7 @@ bool getMetaballSurfaceProperties(const octomap::point3d_list& cloud, const doub else // just get normals, no depth { octomath::Vector3 gradient; + double intensity = 0; if (sampleCloud(cloud, spacing, r_multiple, contact_point, intensity, gradient)) { normal = gradient.normalized(); @@ -211,11 +211,10 @@ bool findSurface(const octomap::point3d_list& cloud, const double& spacing, cons const double& r_multiple, const octomath::Vector3& seed, octomath::Vector3& surface_point, octomath::Vector3& normal) { - const double epsilon = 1e-10; + octomath::Vector3 p = seed, dp, gs; const int iterations = 10; + const double epsilon = 1e-10; double intensity = 0; - - octomath::Vector3 p = seed, dp, gs; for (int i = 0; i < iterations; ++i) { if (!sampleCloud(cloud, spacing, r_multiple, p, intensity, gs)) diff --git a/moveit_core/planning_scene/src/planning_scene.cpp b/moveit_core/planning_scene/src/planning_scene.cpp index ab92e0bf4a..f2876839f8 100644 --- a/moveit_core/planning_scene/src/planning_scene.cpp +++ b/moveit_core/planning_scene/src/planning_scene.cpp @@ -1058,7 +1058,7 @@ bool PlanningScene::loadGeometryFromStream(std::istream& in, const Eigen::Isomet RCLCPP_ERROR(LOGGER, "Failed to read pose from scene file"); return false; } - float r, g, b, a; + double r, g, b, a; if (!(in >> r >> g >> b >> a)) { RCLCPP_ERROR(LOGGER, "Improperly formatted color in scene geometry file"); diff --git a/moveit_core/robot_model/src/floating_joint_model.cpp b/moveit_core/robot_model/src/floating_joint_model.cpp index 1cd5204808..f234728ec6 100644 --- a/moveit_core/robot_model/src/floating_joint_model.cpp +++ b/moveit_core/robot_model/src/floating_joint_model.cpp @@ -173,7 +173,7 @@ bool FloatingJointModel::satisfiesPositionBounds(const double* values, const Bou if (values[2] < bounds[2].min_position_ - margin || values[2] > bounds[2].max_position_ + margin) return false; double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6]; - return fabs(norm_sqr - 1.0) <= std::numeric_limits::epsilon() * 10.0; + return fabs(norm_sqr - 1.0) <= std::numeric_limits::epsilon() * 10.0; } bool FloatingJointModel::normalizeRotation(double* values) const diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index 36424f9098..edf6508f85 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -1287,7 +1287,7 @@ void RobotState::getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, cons if (shapes::constructMarkerFromShape(it.second->getShapes()[j].get(), att_mark)) { // if the object is invisible (0 volume) we skip it - if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits::epsilon()) + if (fabs(att_mark.scale.x * att_mark.scale.y * att_mark.scale.z) < std::numeric_limits::epsilon()) continue; att_mark.pose = tf2::toMsg(it.second->getGlobalCollisionBodyTransforms()[j]); arr.markers.push_back(att_mark); @@ -1313,7 +1313,7 @@ void RobotState::getRobotMarkers(visualization_msgs::msg::MarkerArray& arr, cons if (!shapes::constructMarkerFromShape(link_model->getShapes()[j].get(), mark)) continue; // if the object is invisible (0 volume) we skip it - if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits::epsilon()) + if (fabs(mark.scale.x * mark.scale.y * mark.scale.z) < std::numeric_limits::epsilon()) continue; mark.pose = tf2::toMsg(global_collision_body_transforms_[link_model->getFirstCollisionBodyTransformIndex() + j]); @@ -1488,7 +1488,7 @@ void RobotState::computeVariableVelocity(const JointModelGroup* jmg, Eigen::Vect const Eigen::VectorXd& s = svd_of_j.singularValues(); Eigen::VectorXd sinv = s; - static const double PINVTOLER = std::numeric_limits::epsilon(); + static const double PINVTOLER = std::numeric_limits::epsilon(); double maxsv = 0.0; for (std::size_t i = 0; i < static_cast(s.rows()); ++i) { diff --git a/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp b/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp index cfb3234a44..6e2223da26 100644 --- a/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp +++ b/moveit_planners/ompl/ompl_interface/src/parameterization/work_space/pose_model_state_space.cpp @@ -126,7 +126,7 @@ void ompl_interface::PoseModelStateSpace::copyState(ompl::base::State* destinati void ompl_interface::PoseModelStateSpace::sanityChecks() const { - ModelBasedStateSpace::sanityChecks(std::numeric_limits::epsilon(), std::numeric_limits::epsilon(), + ModelBasedStateSpace::sanityChecks(std::numeric_limits::epsilon(), std::numeric_limits::epsilon(), ~ompl::base::StateSpace::STATESPACE_TRIANGLE_INEQUALITY); } diff --git a/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp b/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp index 3810608b5c..4ec2cd4cdf 100644 --- a/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp +++ b/moveit_ros/hybrid_planning/local_planner/local_planner_component/src/local_planner_component.cpp @@ -51,7 +51,7 @@ const rclcpp::Logger LOGGER = rclcpp::get_logger("local_planner_component"); const auto JOIN_THREAD_TIMEOUT = std::chrono::seconds(1); // If the trajectory progress reaches more than 0.X the global goal state is considered as reached -constexpr float PROGRESS_THRESHOLD = 0.995; +constexpr double PROGRESS_THRESHOLD = 0.995; } // namespace LocalPlannerComponent::LocalPlannerComponent(const rclcpp::NodeOptions& options) diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index c3b1b1f818..ba32c93bf5 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -103,7 +103,7 @@ class DepthImageOctomapUpdater : public OccupancyMapUpdater std::unique_ptr > mesh_filter_; std::unique_ptr free_space_updater_; - std::vector x_cache_, y_cache_; + std::vector x_cache_, y_cache_; double inv_fx_, inv_fy_, K0_, K2_, K4_, K5_; std::vector filtered_labels_; rclcpp::Time last_depth_callback_start_; diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp index dd297f82e6..958bf35a6f 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -445,7 +445,7 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image: debug_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1; debug_msg.step = w * sizeof(float); debug_msg.data.resize(img_size * sizeof(float)); - mesh_filter_->getModelDepth(reinterpret_cast(&debug_msg.data[0])); + mesh_filter_->getModelDepth(reinterpret_cast(&debug_msg.data[0])); pub_model_depth_image_.publish(debug_msg, *info_msg); sensor_msgs::msg::Image filtered_depth_msg; @@ -456,7 +456,7 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image: filtered_depth_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1; filtered_depth_msg.step = w * sizeof(float); filtered_depth_msg.data.resize(img_size * sizeof(float)); - mesh_filter_->getFilteredDepth(reinterpret_cast(&filtered_depth_msg.data[0])); + mesh_filter_->getFilteredDepth(reinterpret_cast(&filtered_depth_msg.data[0])); pub_filtered_depth_image_.publish(filtered_depth_msg, *info_msg); sensor_msgs::msg::Image label_msg; @@ -488,7 +488,7 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::msg::Image: if (filtered_data.size() < img_size) filtered_data.resize(img_size); - mesh_filter_->getFilteredDepth(reinterpret_cast(&filtered_data[0])); + mesh_filter_->getFilteredDepth(reinterpret_cast(&filtered_data[0])); unsigned short* msg_data = reinterpret_cast(&filtered_msg.data[0]); for (std::size_t i = 0; i < img_size; ++i) { diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 92e3441c4c..8707cd2569 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -70,7 +70,7 @@ class GLRenderer * \param[in] near distance of the near clipping plane in meters * \param[in] far distance of the far clipping plane in meters */ - GLRenderer(unsigned width, unsigned height, float near = 0.1, float far = 10.0); + GLRenderer(unsigned width, unsigned height, double near = 0.1, double far = 10.0); /** \brief destructor, destroys frame buffer objects and OpenGL context*/ ~GLRenderer(); @@ -106,7 +106,7 @@ class GLRenderer * \author Suat Gedikli (gedikli@willowgarage.com) * \param[out] buffer pointer to memory where the depth values need to be stored */ - void getDepthBuffer(float* buffer) const; + void getDepthBuffer(double* buffer) const; /** * \brief loads, compiles, links and adds GLSL shaders from files to the current OpenGL context. @@ -135,7 +135,7 @@ class GLRenderer * \param[in] cx x component of principal point * \param[in] cy y component of principal point */ - void setCameraParameters(float fx, float fy, float cx, float cy); + void setCameraParameters(double fx, double fy, double cx, double cy); /** * \brief sets the near and far clipping plane distances in meters @@ -143,21 +143,21 @@ class GLRenderer * \param[in] near distance of the near clipping plane in meters * \param[in] far distance of the far clipping plane in meters */ - void setClippingRange(float near, float far); + void setClippingRange(double near, double far); /** * \brief returns the distance of the near clipping plane in meters * \author Suat Gedikli (gedikli@willowgarage.com) * \return distance of near clipping plane in meters */ - const float& getNearClippingDistance() const; + const double& getNearClippingDistance() const; /** * \brief returns the distance of the far clipping plane in meters * \author Suat Gedikli (gedikli@willowgarage.com) * \return distance of the far clipping plane in meters */ - const float& getFarClippingDistance() const; + const double& getFarClippingDistance() const; /** * \brief returns the width of the frame buffer objectsin pixels @@ -281,10 +281,10 @@ class GLRenderer GLuint program_; /** \brief distance of near clipping plane in meters*/ - float near_; + double near_; /** \brief distance of far clipping plane in meters*/ - float far_; + double far_; /** \brief focal length in x-direction of camera in pixels*/ float fx_; @@ -299,11 +299,11 @@ class GLRenderer float cy_; /** \brief map from thread id to OpenGL context */ - static std::map > context_; + static std::map > context; /* \brief lock for context map */ - static std::mutex context_lock_; + static std::mutex context_lock; - static bool glutInitialized_; + static bool glut_initialized; }; } // namespace mesh_filter diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index c319bdf35f..84fed3c28e 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -131,7 +131,7 @@ class MeshFilterBase * \author Suat Gedikli (gedikli@willowgarage.com) * \param[out] depth pointer to buffer to be filled with depth values. */ - void getFilteredDepth(float* depth) const; + void getFilteredDepth(double* depth) const; /** * \brief retrieves the labels of the rendered model @@ -149,7 +149,7 @@ class MeshFilterBase * \author Suat Gedikli (gedikli@willowgarage.com) * \param[out] depth pointer to buffer to be filled with depth values. */ - void getModelDepth(float* depth) const; + void getModelDepth(double* depth) const; /** * \brief set the shadow threshold. points that are further away than the rendered model are filtered out. diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index 607fb663c0..0ba4405281 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -103,13 +103,13 @@ class SensorModel * \brief transforms depth values from rendered model to metric depth values * \param[in,out] depth pointer to floating point depth buffer */ - virtual void transformModelDepthToMetricDepth(float* depth) const; + virtual void transformModelDepthToMetricDepth(double* depth) const; /** * \brief transforms depth values from filtered depth to metric depth values * \param[in,out] depth pointer to floating point depth buffer */ - virtual void transformFilteredDepthToMetricDepth(float* depth) const; + virtual void transformFilteredDepthToMetricDepth(double* depth) const; /** * \brief sets the image size diff --git a/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp b/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp index f77c692bcc..266d8948ab 100644 --- a/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp +++ b/moveit_ros/perception/mesh_filter/src/depth_self_filter_nodelet.cpp @@ -113,7 +113,7 @@ void mesh_filter::DepthSelfFiltering::filter(const sensor_msgs::ImageConstPtr& d params.setCameraParameters(info_msg->K[0], info_msg->K[4], info_msg->K[2], info_msg->K[5]); params.setImageSize(depth_msg->width, depth_msg->height); - const float* src = (const float*)&depth_msg->data[0]; + const double* src = (const double*)&depth_msg->data[0]; //* static unsigned data_size = 0; static unsigned short* data = nullptr; @@ -135,7 +135,7 @@ void mesh_filter::DepthSelfFiltering::filter(const sensor_msgs::ImageConstPtr& d if (static_cast(filtered_depth_ptr_->image.cols) != depth_msg->width || static_cast(filtered_depth_ptr_->image.rows) != depth_msg->height) filtered_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1); - mesh_filter_->getFilteredDepth((float*)filtered_depth_ptr_->image.data); + mesh_filter_->getFilteredDepth((double*)filtered_depth_ptr_->image.data); pub_filtered_depth_image_.publish(filtered_depth_ptr_->toImageMsg(), info_msg); } @@ -148,7 +148,7 @@ void mesh_filter::DepthSelfFiltering::filter(const sensor_msgs::ImageConstPtr& d if (static_cast(model_depth_ptr_->image.cols) != depth_msg->width || static_cast(model_depth_ptr_->image.rows) != depth_msg->height) model_depth_ptr_->image = cv::Mat(depth_msg->height, depth_msg->width, CV_32FC1); - mesh_filter_->getModelDepth((float*)model_depth_ptr_->image.data); + mesh_filter_->getModelDepth((double*)model_depth_ptr_->image.data); pub_model_depth_image_.publish(model_depth_ptr_->toImageMsg(), info_msg); } diff --git a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp index a1e63ba9dd..e42ed04d94 100644 --- a/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp +++ b/moveit_ros/perception/mesh_filter/src/gl_renderer.cpp @@ -55,7 +55,7 @@ using namespace std; static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.perception.gl_renderer"); -mesh_filter::GLRenderer::GLRenderer(unsigned width, unsigned height, float near, float far) +mesh_filter::GLRenderer::GLRenderer(unsigned width, unsigned height, double near, double far) : width_(width) , height_(height) , fbo_id_(0) @@ -92,7 +92,7 @@ void mesh_filter::GLRenderer::setBufferSize(unsigned width, unsigned height) } } -void mesh_filter::GLRenderer::setClippingRange(float near, float far) +void mesh_filter::GLRenderer::setClippingRange(double near, double far) { if (near_ <= 0) throw runtime_error("near clipping plane distance needs to be larger than 0"); @@ -102,7 +102,7 @@ void mesh_filter::GLRenderer::setClippingRange(float near, float far) far_ = far; } -void mesh_filter::GLRenderer::setCameraParameters(float fx, float fy, float cx, float cy) +void mesh_filter::GLRenderer::setCameraParameters(double fx, double fy, double cx, double cy) { fx_ = fx; fy_ = fy; @@ -112,10 +112,10 @@ void mesh_filter::GLRenderer::setCameraParameters(float fx, float fy, float cx, void mesh_filter::GLRenderer::setCameraParameters() const { - float left = near_ * -cx_ / fx_; - float right = near_ * (width_ - cx_) / fx_; - float top = near_ * cy_ / fy_; - float bottom = near_ * (cy_ - height_) / fy_; + double left = near_ * -cx_ / fx_; + double right = near_ * (width_ - cx_) / fx_; + double top = near_ * cy_ / fy_; + double bottom = near_ * (cy_ - height_) / fy_; glMatrixMode(GL_PROJECTION); glLoadIdentity(); @@ -214,7 +214,7 @@ void mesh_filter::GLRenderer::getColorBuffer(unsigned char* buffer) const glBindFramebuffer(GL_FRAMEBUFFER, 0); } -void mesh_filter::GLRenderer::getDepthBuffer(float* buffer) const +void mesh_filter::GLRenderer::getDepthBuffer(double* buffer) const { glBindFramebuffer(GL_FRAMEBUFFER, fbo_id_); glBindTexture(GL_TEXTURE_2D, depth_id_); @@ -246,12 +246,12 @@ const GLuint& mesh_filter::GLRenderer::getProgramID() const return program_; } -const float& mesh_filter::GLRenderer::getNearClippingDistance() const +const double& mesh_filter::GLRenderer::getNearClippingDistance() const { return near_; } -const float& mesh_filter::GLRenderer::getFarClippingDistance() const +const double& mesh_filter::GLRenderer::getFarClippingDistance() const { return far_; } @@ -357,9 +357,9 @@ GLuint mesh_filter::GLRenderer::loadShaders(const string& vertex_source, const s return program_id; } -map > mesh_filter::GLRenderer::context_; -std::mutex mesh_filter::GLRenderer::context_lock_; -bool mesh_filter::GLRenderer::glutInitialized_ = false; +map > mesh_filter::GLRenderer::context; +std::mutex mesh_filter::GLRenderer::context_lock; +bool mesh_filter::GLRenderer::glut_initialized = false; namespace { @@ -370,8 +370,8 @@ void nullDisplayFunction() void mesh_filter::GLRenderer::createGLContext() { - std::unique_lock _(context_lock_); - if (!glutInitialized_) + std::unique_lock _(context_lock); + if (!glut_initialized) { char buffer[1]; char* args = buffer; @@ -379,16 +379,16 @@ void mesh_filter::GLRenderer::createGLContext() glutInit(&n, &args); glutInitDisplayMode(GLUT_SINGLE | GLUT_RGB | GLUT_DEPTH); - glutInitialized_ = true; + glut_initialized = true; } // check if our thread is initialized std::thread::id thread_id = std::this_thread::get_id(); - map >::iterator context_it = context_.find(thread_id); + map >::iterator context_it = context.find(thread_id); - if (context_it == context_.end()) + if (context_it == context.end()) { - context_[thread_id] = std::pair(1, 0); + context[thread_id] = std::pair(1, 0); glutInitWindowPosition(glutGet(GLUT_SCREEN_WIDTH) + 30000, 0); glutInitWindowSize(1, 1); @@ -409,7 +409,7 @@ void mesh_filter::GLRenderer::createGLContext() for (int i = 0; i < 10; ++i) glutMainLoopEvent(); - context_[thread_id] = std::pair(1, window_id); + context[thread_id] = std::pair(1, window_id); } else ++(context_it->second.first); @@ -417,10 +417,10 @@ void mesh_filter::GLRenderer::createGLContext() void mesh_filter::GLRenderer::deleteGLContext() { - std::unique_lock _(context_lock_); + std::unique_lock _(context_lock); std::thread::id thread_id = std::this_thread::get_id(); - map >::iterator context_it = context_.find(thread_id); - if (context_it == context_.end()) + map >::iterator context_it = context.find(thread_id); + if (context_it == context.end()) { stringstream error_msg; error_msg << "No OpenGL context exists for Thread " << thread_id; @@ -430,7 +430,7 @@ void mesh_filter::GLRenderer::deleteGLContext() if (--(context_it->second.first) == 0) { glutDestroyWindow(context_it->second.second); - context_.erase(context_it); + context.erase(context_it); } } diff --git a/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp b/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp index 6b4b551b9f..793058297e 100644 --- a/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp +++ b/moveit_ros/perception/mesh_filter/src/mesh_filter_base.cpp @@ -227,7 +227,7 @@ void mesh_filter::MeshFilterBase::getModelLabels(LabelType* labels) const job->wait(); } -void mesh_filter::MeshFilterBase::getModelDepth(float* depth) const +void mesh_filter::MeshFilterBase::getModelDepth(double* depth) const { JobPtr job1 = std::make_shared>([&renderer = *mesh_renderer_, depth] { renderer.getDepthBuffer(depth); }); @@ -243,7 +243,7 @@ void mesh_filter::MeshFilterBase::getModelDepth(float* depth) const job2->wait(); } -void mesh_filter::MeshFilterBase::getFilteredDepth(float* depth) const +void mesh_filter::MeshFilterBase::getFilteredDepth(double* depth) const { JobPtr job1 = std::make_shared>([&filter = *depth_filter_, depth] { filter.getDepthBuffer(depth); }); JobPtr job2 = std::make_shared>( diff --git a/moveit_ros/perception/mesh_filter/src/sensor_model.cpp b/moveit_ros/perception/mesh_filter/src/sensor_model.cpp index 9ff5cdbf0c..562e7b4359 100644 --- a/moveit_ros/perception/mesh_filter/src/sensor_model.cpp +++ b/moveit_ros/perception/mesh_filter/src/sensor_model.cpp @@ -102,7 +102,7 @@ inline bool isAligned16(const void* pointer) #endif } // namespace -void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(float* depth) const +void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(double* depth) const { #if HAVE_SSE_EXTENSIONS const __m128 mmNear = _mm_set1_ps(near_clipping_plane_distance_); @@ -161,7 +161,7 @@ void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(floa const float nf = near * far; const float f_n = far - near; - const float* depth_end = depth + width_ * height_; + const double* depth_end = depth + width_ * height_; while (depth < depth_end) { if (*depth != 0 && *depth != 1) @@ -178,7 +178,7 @@ void mesh_filter::SensorModel::Parameters::transformModelDepthToMetricDepth(floa #endif } -void mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth(float* depth) const +void mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth(double* depth) const { #if HAVE_SSE_EXTENSIONS //* SSE version @@ -223,7 +223,7 @@ void mesh_filter::SensorModel::Parameters::transformFilteredDepthToMetricDepth(f ++mmDepth; } #else - const float* depth_end = depth + width_ * height_; + const double* depth_end = depth + width_ * height_; const float scale = far_clipping_plane_distance_ - near_clipping_plane_distance_; const float offset = near_clipping_plane_distance_; while (depth < depth_end) diff --git a/moveit_ros/robot_interaction/src/robot_interaction.cpp b/moveit_ros/robot_interaction/src/robot_interaction.cpp index 14b71ccdde..e85d54cbfd 100644 --- a/moveit_ros/robot_interaction/src/robot_interaction.cpp +++ b/moveit_ros/robot_interaction/src/robot_interaction.cpp @@ -56,8 +56,8 @@ namespace robot_interaction { static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_ros_robot_interaction.robot_interaction"); -static const float END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 }; -static const float END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 }; +static const double END_EFFECTOR_UNREACHABLE_COLOR[4] = { 1.0, 0.3, 0.3, 1.0 }; +static const double END_EFFECTOR_REACHABLE_COLOR[4] = { 0.2, 1.0, 0.2, 1.0 }; const std::string RobotInteraction::INTERACTIVE_MARKER_TOPIC = "robot_interaction_interactive_marker_topic"; @@ -419,7 +419,7 @@ void RobotInteraction::addEndEffectorMarkers(const InteractionHandlerPtr& handle } std_msgs::msg::ColorRGBA marker_color; - const float* color = handler->inError(eef) ? END_EFFECTOR_UNREACHABLE_COLOR : END_EFFECTOR_REACHABLE_COLOR; + const double* color = handler->inError(eef) ? END_EFFECTOR_UNREACHABLE_COLOR : END_EFFECTOR_REACHABLE_COLOR; marker_color.r = color[0]; marker_color.g = color[1]; marker_color.b = color[2]; diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index 17b02924e5..62cfcd0995 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -213,7 +213,7 @@ private Q_SLOTS: void onRobotModelLoaded() override; void onNewPlanningSceneState() override; void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type) override; - void updateInternal(float wall_dt, float ros_dt) override; + void updateInternal(double wall_dt, double ros_dt) override; void renderWorkspaceBox(); void updateLinkColors(); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index 60ff93fbec..20190830d0 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -121,7 +121,7 @@ class MotionPlanningFrame : public QWidget void initFromMoveGroupNS(); void constructPlanningRequest(moveit_msgs::msg::MotionPlanRequest& mreq); - void updateSceneMarkers(float wall_dt, float ros_dt); + void updateSceneMarkers(double wall_dt, double ros_dt); void updateExternalCommunication(); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h index ee15f6521c..76dd1cd4e2 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame_joints_widget.h @@ -184,23 +184,23 @@ private Q_SLOTS: class ProgressBarEditor : public QWidget { Q_OBJECT - Q_PROPERTY(float value READ getValue WRITE setValue NOTIFY valueChanged USER true) + Q_PROPERTY(double value READ getValue WRITE setValue NOTIFY valueChanged USER true) public: /// Create a progressbar-like slider for editing values in range mix..max - ProgressBarEditor(QWidget* parent = nullptr, float min = -1.0, float max = 0.0, int digits = 0); + ProgressBarEditor(QWidget* parent = nullptr, double min = -1.0, double max = 0.0, int digits = 0); - void setValue(float value) + void setValue(double value) { value_ = value; } - float getValue() const + double getValue() const { return value_; } Q_SIGNALS: - void valueChanged(float value); + void valueChanged(double value); void editingFinished(); protected: @@ -210,9 +210,9 @@ class ProgressBarEditor : public QWidget void mouseReleaseEvent(QMouseEvent* event) override; private: - float value_; - float min_; - float max_; + double value_; + double min_; + double max_; int digits_; ///< number of decimal digits for formatting of the value }; diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp index fb8b43c7bd..7dd4ce0ee6 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_display.cpp @@ -1342,7 +1342,7 @@ void MotionPlanningDisplay::update(float wall_dt, float ros_dt) PlanningSceneDisplay::update(wall_dt, ros_dt); } -void MotionPlanningDisplay::updateInternal(float wall_dt, float ros_dt) +void MotionPlanningDisplay::updateInternal(double wall_dt, double ros_dt) { PlanningSceneDisplay::updateInternal(wall_dt, ros_dt); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp index b6cbabab73..af37922f46 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame.cpp @@ -673,7 +673,7 @@ void MotionPlanningFrame::tabChanged(int index) } } -void MotionPlanningFrame::updateSceneMarkers(float /*wall_dt*/, float /*ros_dt*/) +void MotionPlanningFrame::updateSceneMarkers(double /*wall_dt*/, double /*ros_dt*/) { if (scene_marker_) scene_marker_->update(); diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp index f9415cb478..3614f102cc 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_joints_widget.cpp @@ -423,8 +423,8 @@ void ProgressBarDelegate::paint(QPainter* painter, const QStyleOptionViewItem& o if (vbounds.isValid()) { QPointF bounds = vbounds.toPointF(); - const float min = bounds.x(); - const float max = bounds.y(); + const double min = bounds.x(); + const double max = bounds.y(); QStyleOptionProgressBar opt; opt.rect = option.rect; @@ -452,8 +452,8 @@ QWidget* ProgressBarDelegate::createEditor(QWidget* parent, const QStyleOptionVi if (vbounds.isValid()) { QPointF bounds = vbounds.toPointF(); - float min = bounds.x(); - float max = bounds.y(); + double min = bounds.x(); + double max = bounds.y(); bool is_revolute = (index.data(JointTypeRole).toInt() == moveit::core::JointModel::REVOLUTE); if (is_revolute) { @@ -462,7 +462,7 @@ QWidget* ProgressBarDelegate::createEditor(QWidget* parent, const QStyleOptionVi } auto* editor = new ProgressBarEditor(parent, min, max, is_revolute ? 0 : 3); connect(editor, &ProgressBarEditor::editingFinished, this, &ProgressBarDelegate::commitAndCloseEditor); - connect(editor, &ProgressBarEditor::valueChanged, this, [=](float value) { + connect(editor, &ProgressBarEditor::valueChanged, this, [=](double value) { const_cast(index.model())->setData(index, value, Qt::EditRole); }); return editor; @@ -498,7 +498,7 @@ bool JointsWidgetEventFilter::eventFilter(QObject* /*target*/, QEvent* event) return false; } -ProgressBarEditor::ProgressBarEditor(QWidget* parent, float min, float max, int digits) +ProgressBarEditor::ProgressBarEditor(QWidget* parent, double min, double max, int digits) : QWidget(parent), min_(min), max_(max), digits_(digits) { // if left mouse button is pressed, grab all future mouse events until button(s) released @@ -530,7 +530,7 @@ void ProgressBarEditor::mousePressEvent(QMouseEvent* event) void ProgressBarEditor::mouseMoveEvent(QMouseEvent* event) { - float v = std::min(max_, std::max(min_, min_ + event->x() * (max_ - min_) / width())); + double v = std::min(max_, std::max(min_, min_ + event->x() * (max_ - min_) / width())); if (value_ != v) { value_ = v; diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index 6207edeae7..3e37370448 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -178,7 +178,7 @@ protected Q_SLOTS: void fixedFrameChanged() override; // new virtual functions added by this plugin - virtual void updateInternal(float wall_dt, float ros_dt); + virtual void updateInternal(double wall_dt, double ros_dt); virtual void onSceneMonitorReceivedUpdate(planning_scene_monitor::PlanningSceneMonitor::SceneUpdateType update_type); planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_; @@ -199,7 +199,7 @@ protected Q_SLOTS: bool planning_scene_needs_render_; // or only the robot position (excluding attached object changes) bool robot_state_needs_render_; - float current_scene_time_; + double current_scene_time_; rviz_common::properties::Property* scene_category_; rviz_common::properties::Property* robot_category_; diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp index 0caafa535f..75de575ec9 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/src/planning_scene_display.cpp @@ -670,7 +670,7 @@ void PlanningSceneDisplay::update(float wall_dt, float ros_dt) updateInternal(wall_dt, ros_dt); } -void PlanningSceneDisplay::updateInternal(float wall_dt, float /*ros_dt*/) +void PlanningSceneDisplay::updateInternal(double wall_dt, double /*ros_dt*/) { current_scene_time_ += wall_dt; if (planning_scene_render_ && diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index 0dc4a46ba5..06ab1d8fda 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -70,7 +70,7 @@ class PlanningSceneRender void renderPlanningScene(const planning_scene::PlanningSceneConstPtr& scene, const Ogre::ColourValue& default_scene_color, const Ogre::ColourValue& default_attached_color, OctreeVoxelRenderMode voxel_render_mode, - OctreeVoxelColorMode voxel_color_mode, float default_scene_alpha); + OctreeVoxelColorMode voxel_color_mode, double default_scene_alpha); void clear(); private: diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index d0838a097f..c7d7d3fcaf 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -59,8 +59,8 @@ class RenderShapes void renderShape(Ogre::SceneNode* node, const shapes::Shape* s, const Eigen::Isometry3d& p, OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode, - const Ogre::ColourValue& color, float alpha); - void updateShapeColors(float r, float g, float b, float a); + const Ogre::ColourValue& color, double alpha); + void updateShapeColors(double r, double g, double b, double a); void clear(); private: diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index f04e32fd55..fae4c85c29 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -95,7 +95,7 @@ class RobotStateVisualization */ void setCollisionVisible(bool visible); - void setAlpha(float alpha); + void setAlpha(double alpha); private: void updateHelper(const moveit::core::RobotStateConstPtr& robot_state, diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 4fb7bd0190..48a16ad598 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -87,7 +87,7 @@ class TrajectoryVisualization : public QObject ~TrajectoryVisualization() override; - virtual void update(float wall_dt, float sim_dt); + virtual void update(double wall_dt, double sim_dt); virtual void reset(); void onInitialize(const rclcpp::Node::SharedPtr& node, Ogre::SceneNode* scene_node, @@ -132,7 +132,7 @@ private Q_SLOTS: * \return Positive values indicate a fixed time per state * Negative values indicate a realtime-factor */ - float getStateDisplayTime(); + double getStateDisplayTime(); void clearTrajectoryTrail(); // Handles actually drawing the robot along motion plans @@ -150,7 +150,7 @@ private Q_SLOTS: bool animating_path_; bool drop_displaying_trajectory_; int current_state_; - float current_state_time_; + double current_state_time_; std::mutex update_trajectory_message_; moveit::core::RobotModelConstPtr robot_model_; diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp index 8513ea8997..5a36c4d082 100755 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/octomap_render.cpp @@ -224,7 +224,7 @@ void OcTreeRender::octreeDecoding(const std::shared_ptr& new_point.position.y = it.getY(); new_point.position.z = it.getZ(); - float cell_probability; + double cell_probability; switch (octree_color_mode) { diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp index e9bb41b4e2..d5ebca65e2 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp @@ -75,7 +75,7 @@ void PlanningSceneRender::renderPlanningScene(const planning_scene::PlanningScen const Ogre::ColourValue& default_env_color, const Ogre::ColourValue& default_attached_color, OctreeVoxelRenderMode octree_voxel_rendering, - OctreeVoxelColorMode octree_color_mode, float default_scene_alpha) + OctreeVoxelColorMode octree_color_mode, double default_scene_alpha) { if (!scene) return; @@ -102,7 +102,7 @@ void PlanningSceneRender::renderPlanningScene(const planning_scene::PlanningScen { collision_detection::CollisionEnv::ObjectConstPtr object = scene->getWorld()->getObject(id); Ogre::ColourValue color = default_env_color; - float alpha = default_scene_alpha; + double alpha = default_scene_alpha; if (scene->hasObjectColor(id)) { const std_msgs::msg::ColorRGBA& c = scene->getObjectColor(id); diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp index 73c2b38654..dc340cd4ae 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/render_shapes.cpp @@ -71,7 +71,7 @@ void RenderShapes::clear() void RenderShapes::renderShape(Ogre::SceneNode* node, const shapes::Shape* s, const Eigen::Isometry3d& p, OctreeVoxelRenderMode octree_voxel_rendering, OctreeVoxelColorMode octree_color_mode, - const Ogre::ColourValue& color, float alpha) + const Ogre::ColourValue& color, double alpha) { rviz_rendering::Shape* ogre_shape = nullptr; Eigen::Vector3d translation = p.translation(); @@ -192,7 +192,7 @@ void RenderShapes::renderShape(Ogre::SceneNode* node, const shapes::Shape* s, co } } -void RenderShapes::updateShapeColors(float r, float g, float b, float a) +void RenderShapes::updateShapeColors(double r, double g, double b, double a) { for (const std::unique_ptr& shape : scene_shapes_) shape->setColor(r, g, b, a); diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp index b8e105ba53..2af820fa44 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/robot_state_visualization.cpp @@ -119,7 +119,7 @@ void RobotStateVisualization::updateHelper(const moveit::core::RobotStateConstPt for (const moveit::core::AttachedBody* attached_body : attached_bodies) { std_msgs::msg::ColorRGBA color = default_attached_object_color; - float alpha = robot_.getAlpha(); + double alpha = robot_.getAlpha(); if (color_map) { std::map::const_iterator it = color_map->find(attached_body->getName()); @@ -176,7 +176,7 @@ void RobotStateVisualization::setCollisionVisible(bool visible) robot_.setCollisionVisible(visible); } -void RobotStateVisualization::setAlpha(float alpha) +void RobotStateVisualization::setAlpha(double alpha) { robot_.setAlpha(alpha); } diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp index 0c2f7c6990..1b82869435 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/trajectory_visualization.cpp @@ -364,15 +364,15 @@ void TrajectoryVisualization::interruptCurrentDisplay() animating_path_ = false; } -float TrajectoryVisualization::getStateDisplayTime() +double TrajectoryVisualization::getStateDisplayTime() { constexpr char default_time_string[] = "3x"; - constexpr float default_time_value = -3.0f; + constexpr double default_time_value = -3.0; std::string tm = state_display_time_property_->getStdString(); boost::trim(tm); - float type; + double type; if (tm.back() == 'x') { @@ -391,7 +391,7 @@ float TrajectoryVisualization::getStateDisplayTime() tm.resize(tm.size() - 1); boost::trim_right(tm); - float value; + double value; try { value = std::stof(tm); @@ -416,7 +416,7 @@ void TrajectoryVisualization::dropTrajectory() drop_displaying_trajectory_ = true; } -void TrajectoryVisualization::update(float wall_dt, float sim_dt) +void TrajectoryVisualization::update(double wall_dt, double sim_dt) { if (drop_displaying_trajectory_) { @@ -478,7 +478,7 @@ void TrajectoryVisualization::update(float wall_dt, float sim_dt) { current_state_time_ += wall_dt; } - float tm = getStateDisplayTime(); + double tm = getStateDisplayTime(); if (trajectory_slider_panel_ && trajectory_slider_panel_->isVisible() && trajectory_slider_panel_->isPaused()) { @@ -493,7 +493,7 @@ void TrajectoryVisualization::update(float wall_dt, float sim_dt) else if (tm < 0.0) { // using realtime factors: skip to next waypoint based on elapsed display time - const float rt_factor = -tm; // negative tm is the intended realtime factor + const double rt_factor = -tm; // negative tm is the intended realtime factor while (current_state_ < waypoint_count && (tm = displaying_trajectory_message_->getWayPointDurationFromPrevious(current_state_ + 1) / rt_factor) < current_state_time_)