Skip to content
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ SCALAR_T trapezoidalIntegration(const std::vector<SCALAR_T>& timeTrajectory, con
}

SCALAR_T areaUnderCurve = 0.0;
for (size_t k = 1; k < timeTrajectory.size(); k++) {
for (std::size_t k = 1; k < timeTrajectory.size(); k++) {
areaUnderCurve += 0.5 * (valueTrajectory[k] + valueTrajectory[k - 1]) * (timeTrajectory[k] - timeTrajectory[k - 1]);
} // end of k loop

Expand Down
7 changes: 6 additions & 1 deletion ocs2_pinocchio/ocs2_centroidal_model/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@ find_package(ocs2_core REQUIRED)
find_package(ocs2_robotic_tools REQUIRED)
find_package(ocs2_pinocchio_interface REQUIRED)
find_package(OpenMP REQUIRED)

find_package(urdf)
find_package(urdfdom)
find_package(Boost REQUIRED COMPONENTS
system
filesystem
Expand Down Expand Up @@ -66,6 +67,8 @@ ament_target_dependencies(${PROJECT_NAME}
ocs2_pinocchio_interface
ocs2_core
ocs2_robotic_tools
urdf
urdfdom
)

set_target_properties(${PROJECT_NAME}
Expand Down Expand Up @@ -111,6 +114,8 @@ ament_export_dependencies(ocs2_core)
ament_export_dependencies(ocs2_robotic_tools)
ament_export_dependencies(ocs2_thirdparty)
ament_export_dependencies(ocs2_pinocchio_interface)
ament_export_dependencies(urdf)
ament_export_dependencies(urdfdom)

#############
## Testing ##
Expand Down
6 changes: 6 additions & 0 deletions ocs2_pinocchio/ocs2_pinocchio_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@ find_package(ocs2_robotic_tools REQUIRED)
find_package(ocs2_oc REQUIRED)
find_package(ocs2_thirdparty REQUIRED)
find_package(OpenMP REQUIRED)
find_package(urdf REQUIRED)
find_package(urdfdom REQUIRED)

find_package(Boost REQUIRED COMPONENTS
system
Expand Down Expand Up @@ -77,6 +79,8 @@ ament_target_dependencies(${PROJECT_NAME}
ocs2_core
ocs2_oc
ocs2_robotic_tools
urdf
urdfdom
)

target_link_libraries(${PROJECT_NAME}
Expand Down Expand Up @@ -127,6 +131,8 @@ ament_export_targets(

ament_export_dependencies(ocs2_core)
ament_export_dependencies(ocs2_robotic_tools)
ament_export_dependencies(urdf)
ament_export_dependencies(urdfdom)

############
# Testing ##
Expand Down
2 changes: 2 additions & 0 deletions ocs2_pinocchio/ocs2_pinocchio_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
<depend>ocs2_core</depend>
<depend>ocs2_oc</depend>
<depend>ocs2_robotic_tools</depend>
<depend>urdf</depend>
<depend>urdfdom</depend>
<depend>pinocchio</depend>

<export>
Expand Down
2 changes: 2 additions & 0 deletions ocs2_robotic_examples/ocs2_legged_robot_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,7 @@ set(AMENT_PACKAGE_DEPENDENCIES
tf2
tf2_ros
urdf
urdfdom
kdl_parser
rclcpp
robot_state_publisher
Expand Down Expand Up @@ -307,6 +308,7 @@ ament_export_dependencies(ocs2_centroidal_model)
ament_export_dependencies(ocs2_ros_interfaces)
ament_export_dependencies(tf2)
ament_export_dependencies(urdf)
ament_export_dependencies(urdfdom)
ament_export_dependencies(kdl_parser)
ament_export_dependencies(robot_state_publisher)
ament_export_dependencies(visualization_msgs)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -163,8 +163,7 @@ void LeggedRobotVisualizer::publishTrajectory(const std::vector<SystemObservatio
scalar_t frameDuration = speed * (system_observation_array[k + 1].time - system_observation_array[k].time);
scalar_t publishDuration = timedExecutionInSeconds([&]() { publishObservation(nodeHandle_->now(), system_observation_array[k]); });
if (frameDuration > publishDuration) {
rclcpp::Duration dur(frameDuration - publishDuration);
rclcpp::sleep_for(std::chrono::nanoseconds(dur.nanoseconds()));
rclcpp::sleep_for(std::chrono::nanoseconds(int((frameDuration - publishDuration)*1e9)));
}
}
}
Expand Down
5 changes: 2 additions & 3 deletions ocs2_ros_interfaces/src/mrt/MRT_ROS_Dummy_Loop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ MRT_ROS_Dummy_Loop::MRT_ROS_Dummy_Loop(MRT_ROS_Interface& mrt, scalar_t mrtDesir
/******************************************************************************************************/
void MRT_ROS_Dummy_Loop::run(const SystemObservation& initObservation, const TargetTrajectories& initTargetTrajectories) {
RCLCPP_INFO_STREAM(LOGGER, "Waiting for the initial policy ...");
const scalar_t timeStep = (1.0 / mrtDesiredFrequency_);
const double timeStep = (1.0 / mrtDesiredFrequency_);
// Reset MPC node
mrt_.resetMpcNode(initTargetTrajectories);

Expand All @@ -61,8 +61,7 @@ void MRT_ROS_Dummy_Loop::run(const SystemObservation& initObservation, const Tar
mrt_.spinMRT();
mrt_.setCurrentObservation(initObservation);

int16_t sleeptime = rclcpp::Duration(timeStep).nanoseconds();
rclcpp::sleep_for(std::chrono::nanoseconds(sleeptime));
rclcpp::sleep_for(std::chrono::nanoseconds(int(timeStep * 1e9)));
}
RCLCPP_INFO_STREAM(LOGGER, "Initial policy has been received.");

Expand Down