Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add missing dependency on angles and update formatting for linters. #283

Merged
merged 5 commits into from
Jan 29, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions ur_calibration/include/ur_calibration/calibration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,14 +29,14 @@
#ifndef UR_CALIBRATION__CALIBRATION_HPP_
#define UR_CALIBRATION__CALIBRATION_HPP_

#include <rclcpp/rclcpp.hpp>
#include <Eigen/Dense>
#include <yaml-cpp/yaml.h>

#include <fstream>
#include <string>
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "yaml-cpp/yaml.h"

namespace ur_calibration
{
/*!
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@

#ifndef UR_CALIBRATION__CALIBRATION_CONSUMER_HPP_
#define UR_CALIBRATION__CALIBRATION_CONSUMER_HPP_
#include <ur_client_library/comm/pipeline.h>

#include <ur_client_library/primary/robot_state/kinematics_info.h>
#include <memory>

#include <ur_calibration/calibration.hpp>
#include "ur_client_library/comm/pipeline.h"
#include "ur_client_library/primary/robot_state/kinematics_info.h"

#include <memory>
#include "ur_calibration/calibration.hpp"

namespace ur_calibration
{
Expand Down
3 changes: 2 additions & 1 deletion ur_calibration/src/calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,8 @@
*/
//----------------------------------------------------------------------

#include <ur_calibration/calibration.hpp>
#include "ur_calibration/calibration.hpp"

#include <vector>

namespace ur_calibration
Expand Down
2 changes: 1 addition & 1 deletion ur_calibration/src/calibration_consumer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
*/
//----------------------------------------------------------------------

#include <ur_calibration/calibration_consumer.hpp>
#include "ur_calibration/calibration_consumer.hpp"

#include <memory>

Expand Down
30 changes: 15 additions & 15 deletions ur_calibration/src/calibration_correction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,26 +26,26 @@
*/
//----------------------------------------------------------------------

#include <ur_calibration/calibration_consumer.hpp>

#include <ur_client_library/comm/parser.h>
#include <ur_client_library/comm/pipeline.h>
#include <ur_client_library/comm/producer.h>
#include <ur_client_library/comm/stream.h>
#include <ur_client_library/primary/package_header.h>
#include <ur_client_library/primary/primary_parser.h>

#include <ur_robot_driver/urcl_log_handler.hpp>

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <rclcpp/exceptions/exceptions.hpp>
#include <sensor_msgs/msg/joint_state.hpp>
#include <tf2_ros/transform_listener.h>
#include "ur_calibration/calibration_consumer.hpp"

#include <filesystem>
#include <memory>
#include <string>

#include "ur_client_library/comm/parser.h"
#include "ur_client_library/comm/pipeline.h"
#include "ur_client_library/comm/producer.h"
#include "ur_client_library/comm/stream.h"
#include "ur_client_library/primary/package_header.h"
#include "ur_client_library/primary/primary_parser.h"

#include "ur_robot_driver/urcl_log_handler.hpp"

#include "ament_index_cpp/get_package_share_directory.hpp"
#include "rclcpp/exceptions/exceptions.hpp"
#include "sensor_msgs/msg/joint_state.hpp"
#include "tf2_ros/transform_listener.h"

namespace fs = std::filesystem;

using urcl::UrException;
Expand Down
2 changes: 2 additions & 0 deletions ur_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(angles REQUIRED)
find_package(control_msgs REQUIRED)
find_package(controller_interface REQUIRED)
find_package(geometry_msgs REQUIRED)
Expand All @@ -27,6 +28,7 @@ find_package(ur_dashboard_msgs REQUIRED)
find_package(ur_msgs REQUIRED)

set(THIS_PACKAGE_INCLUDE_DEPENDS
angles
control_msgs
controller_interface
geometry_msgs
Expand Down
1 change: 1 addition & 0 deletions ur_controllers/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>angles</depend>
<depend>control_msgs</depend>
<depend>controller_interface</depend>
<depend>geometry_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/src/urcl_log_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ UrclLogHandler::UrclLogHandler() = default;

void UrclLogHandler::log(const char* file, int line, urcl::LogLevel loglevel, const char* message)
{
rcutils_log_location_t location = { "", file, (size_t)line };
rcutils_log_location_t location = { "", file, static_cast<size_t>(line) };
switch (loglevel) {
case urcl::LogLevel::DEBUG:
rcutils_log(&location, RCUTILS_LOG_SEVERITY::RCUTILS_LOG_SEVERITY_DEBUG, "UR_Client_Library", "%s", message);
Expand Down