Skip to content

Commit 59671b8

Browse files
committed
Fix compiler warnings
- declare qhull includes as SYSTEM - fix uninitialized Vector3d usage
1 parent 192801c commit 59671b8

File tree

2 files changed

+2
-2
lines changed

2 files changed

+2
-2
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -105,7 +105,7 @@ target_link_libraries(${PROJECT_NAME}
105105
rclcpp::rclcpp
106106
resource_retriever::resource_retriever
107107
)
108-
target_include_directories(${PROJECT_NAME} PRIVATE ${QHULL_INCLUDE_DIRS})
108+
target_include_directories(${PROJECT_NAME} SYSTEM PRIVATE ${QHULL_INCLUDE_DIRS})
109109

110110
if(BUILD_TESTING)
111111
# Unit tests

src/bodies.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -868,7 +868,7 @@ void bodies::ConvexMesh::useDimensions(const shapes::Shape* shape)
868868
mesh_data_->triangles_.clear();
869869
mesh_data_->vertices_.clear();
870870
mesh_data_->mesh_radiusB_ = 0.0;
871-
mesh_data_->mesh_center_ = Eigen::Vector3d();
871+
mesh_data_->mesh_center_ = Eigen::Vector3d::Zero();
872872

873873
double xdim = maxX - minX;
874874
double ydim = maxY - minY;

0 commit comments

Comments
 (0)