Skip to content

Commit d92fe0e

Browse files
bijoua29mergify[bot]
authored andcommitted
Fix severe warning from class loader in servo (#3577)
* Add class loader member variable instead of creating on stack * Fix formatting to satisfy clang --------- Co-authored-by: AndyZe <[email protected]> Co-authored-by: Nathan Brooks <[email protected]> (cherry picked from commit 92654dd) # Conflicts: # moveit_ros/moveit_servo/include/moveit_servo/servo.hpp # moveit_ros/moveit_servo/src/servo.cpp
1 parent 5397933 commit d92fe0e

File tree

2 files changed

+279
-0
lines changed

2 files changed

+279
-0
lines changed
Lines changed: 253 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,253 @@
1+
/*******************************************************************************
2+
* BSD 3-Clause License
3+
*
4+
* Copyright (c) 2019, Los Alamos National Security, LLC
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions are met:
9+
*
10+
* * Redistributions of source code must retain the above copyright notice, this
11+
* list of conditions and the following disclaimer.
12+
*
13+
* * Redistributions in binary form must reproduce the above copyright notice,
14+
* this list of conditions and the following disclaimer in the documentation
15+
* and/or other materials provided with the distribution.
16+
*
17+
* * Neither the name of the copyright holder nor the names of its
18+
* contributors may be used to endorse or promote products derived from
19+
* this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22+
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23+
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24+
* ARE
25+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26+
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27+
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28+
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30+
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31+
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32+
*******************************************************************************/
33+
34+
/* Title : servo.hpp
35+
* Project : moveit_servo
36+
* Created : 05/17/2023
37+
* Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim
38+
*
39+
* Description : The core servoing logic.
40+
*/
41+
42+
#pragma once
43+
44+
#include <rclcpp/logger.hpp>
45+
#include <rclcpp/version.h>
46+
47+
#include <moveit_servo/collision_monitor.hpp>
48+
#include <moveit_servo/moveit_servo_lib_parameters.hpp>
49+
#include <moveit_servo/utils/command.hpp>
50+
#include <moveit_servo/utils/datatypes.hpp>
51+
#include <moveit/kinematics_base/kinematics_base.hpp>
52+
#include <moveit/online_signal_smoothing/smoothing_base_class.hpp>
53+
#include <moveit/planning_scene_monitor/planning_scene_monitor.hpp>
54+
#include <pluginlib/class_loader.hpp>
55+
#include <sensor_msgs/msg/joint_state.hpp>
56+
#include <tf2_eigen/tf2_eigen.hpp>
57+
// For Rolling, Kilted, and newer
58+
#if RCLCPP_VERSION_GTE(29, 6, 0)
59+
#include <tf2_ros/transform_listener.hpp>
60+
// For Jazzy and older
61+
#else
62+
#include <tf2_ros/transform_listener.h>
63+
#endif
64+
#include <variant>
65+
#include <queue>
66+
67+
namespace moveit_servo
68+
{
69+
70+
class Servo
71+
{
72+
public:
73+
Servo(const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::ParamListener> servo_param_listener,
74+
const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
75+
76+
~Servo();
77+
78+
// Disable copy construction.
79+
Servo(const Servo&) = delete;
80+
81+
// Disable copy assignment.
82+
Servo& operator=(Servo&) = delete;
83+
84+
/**
85+
* \brief Computes the joint state required to follow the given command.
86+
* @param robot_state RobotStatePtr instance used for calculating the next joint state.
87+
* @param command The command to follow, std::variant type, can handle JointJog, Twist and Pose.
88+
* @return The required joint state.
89+
*/
90+
KinematicState getNextJointState(const moveit::core::RobotStatePtr& robot_state, const ServoInput& command);
91+
92+
/**
93+
* \brief Set the type of incoming servo command.
94+
* @param command_type The type of command servo should expect.
95+
*/
96+
void setCommandType(const CommandType& command_type);
97+
98+
/**
99+
* \brief Get the type of command that servo is currently expecting.
100+
* @return The type of command.
101+
*/
102+
CommandType getCommandType() const;
103+
104+
/**
105+
* \brief Get the current status of servo.
106+
* @return The current status.
107+
*/
108+
StatusCode getStatus() const;
109+
110+
/**
111+
* \brief Get the message associated with the current servo status.
112+
* @return The status message.
113+
*/
114+
std::string getStatusMessage() const;
115+
116+
/**
117+
* \brief Start/Stop collision checking thread.
118+
* @param check_collision Stops collision checking thread if false, starts it if true.
119+
*/
120+
void setCollisionChecking(const bool check_collision);
121+
122+
/**
123+
* \brief Returns the most recent servo parameters.
124+
* @return The servo parameters.
125+
*/
126+
servo::Params& getParams();
127+
128+
/**
129+
* \brief Get the current state of the robot as given by planning scene monitor.
130+
* This may block if a current robot state is not available immediately.
131+
* @param block_for_current_state If true, we explicitly wait for a new robot state
132+
* @return The current state of the robot.
133+
*/
134+
KinematicState getCurrentRobotState(bool block_for_current_state) const;
135+
136+
/**
137+
* \brief Smoothly halt at a commanded state when command goes stale.
138+
* @param halt_state The desired halting state.
139+
* @return A pair where the first element is a Boolean indicating whether the robot has stopped, and the second is a
140+
* state stepping towards the desired halting state.
141+
*/
142+
std::pair<bool, KinematicState> smoothHalt(const KinematicState& halt_state);
143+
144+
/**
145+
* \brief Applies smoothing to an input state, if a smoothing plugin is set.
146+
* @param state The state to be updated by the smoothing plugin.
147+
*/
148+
void doSmoothing(KinematicState& state);
149+
150+
/**
151+
* \brief Resets the smoothing plugin, if set, to a specified state.
152+
* @param state The desired state to reset the smoothing plugin to.
153+
*/
154+
void resetSmoothing(const KinematicState& state);
155+
156+
private:
157+
/**
158+
* \brief Finds the transform from the planning frame to a specified command frame.
159+
* If the command frame is part of the robot model, directly look up the transform using the robot model.
160+
* Else, fall back to using TF to look up the transform.
161+
* @param command_frame The command frame name.
162+
* @param planning_frame The planning frame name.
163+
* @return The transformation between planning frame and command frame, or std::nullopt if there was a failure looking
164+
* up a transform.
165+
*/
166+
std::optional<Eigen::Isometry3d> getPlanningToCommandFrameTransform(const std::string& command_frame,
167+
const std::string& planning_frame) const;
168+
169+
/**
170+
* \brief Convert a given twist command to planning frame,
171+
* The command frame specified by `command.frame_id` is expected to be a stationary frame or end-effector frame.
172+
* References:
173+
* https://core.ac.uk/download/pdf/154240607.pdf
174+
* https://www.seas.upenn.edu/~meam520/notes02/Forces8.pdf
175+
* @param command The twist command to be converted.
176+
* @param planning_frame The name of the planning frame.
177+
* @return The transformed twist command.
178+
*/
179+
std::optional<TwistCommand> toPlanningFrame(const TwistCommand& command, const std::string& planning_frame) const;
180+
181+
/**
182+
* \brief Convert a given pose command to planning frame
183+
* @param command The pose command to be converted.
184+
* @param planning_frame The name of the planning frame.
185+
* @return The transformed pose command.
186+
*/
187+
std::optional<PoseCommand> toPlanningFrame(const PoseCommand& command, const std::string& planning_frame) const;
188+
189+
/**
190+
* \brief Compute the change in joint position required to follow the received command.
191+
* @param command The incoming servo command.
192+
* @param robot_state RobotStatePtr instance used for calculating the command.
193+
* @return The joint position change required (delta).
194+
*/
195+
Eigen::VectorXd jointDeltaFromCommand(const ServoInput& command, const moveit::core::RobotStatePtr& robot_state);
196+
197+
/**
198+
* \brief Validate the servo parameters
199+
* @param servo_params The servo parameters
200+
* @return True if parameters are valid, else False
201+
*/
202+
bool validateParams(const servo::Params& servo_params);
203+
204+
/**
205+
* \brief Updates the servo parameters and performs validations.
206+
*/
207+
bool updateParams();
208+
209+
/**
210+
* \brief Create and initialize the smoothing plugin to be used by servo.
211+
*/
212+
void setSmoothingPlugin();
213+
214+
/**
215+
* \brief Apply halting logic to specified joints.
216+
* @param joints_to_halt The indices of joints to be halted.
217+
* @param current_state The current kinematic state.
218+
* @param target_state The target kinematic state.
219+
* @return The bounded kinematic state.
220+
*/
221+
KinematicState haltJoints(const std::vector<size_t>& joints_to_halt, const KinematicState& current_state,
222+
const KinematicState& target_state) const;
223+
224+
// Variables
225+
226+
StatusCode servo_status_;
227+
// This needs to be threadsafe so it can be updated in realtime.
228+
std::atomic<CommandType> expected_command_type_;
229+
230+
servo::Params servo_params_;
231+
const rclcpp::Node::SharedPtr node_;
232+
rclcpp::Logger logger_;
233+
std::shared_ptr<const servo::ParamListener> servo_param_listener_;
234+
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
235+
236+
// This value will be updated by CollisionMonitor in a separate thread.
237+
std::atomic<double> collision_velocity_scale_ = 1.0;
238+
std::unique_ptr<CollisionMonitor> collision_monitor_;
239+
240+
// Plugin loader
241+
std::unique_ptr<pluginlib::ClassLoader<online_signal_smoothing::SmoothingBaseClass>> smoother_loader_;
242+
243+
// Pointer to the (optional) smoothing plugin.
244+
pluginlib::UniquePtr<online_signal_smoothing::SmoothingBaseClass> smoother_ = nullptr;
245+
246+
// Map between joint subgroup names and corresponding joint name - move group indices map
247+
std::unordered_map<std::string, JointNameToMoveGroupIndexMap> joint_name_to_index_maps_;
248+
249+
// The current joint limit safety margins for each active joint position variable.
250+
std::vector<double> joint_limit_margins_;
251+
};
252+
253+
} // namespace moveit_servo

moveit_ros/moveit_servo/src/servo.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,8 +83,34 @@ Servo::~Servo()
8383

8484
void Servo::setPaused(bool paused)
8585
{
86+
<<<<<<< HEAD
8687
servo_calcs_.setPaused(paused);
8788
collision_checker_.setPaused(paused);
89+
=======
90+
// Load the smoothing plugin
91+
try
92+
{
93+
smoother_loader_ = std::make_unique<pluginlib::ClassLoader<online_signal_smoothing::SmoothingBaseClass>>(
94+
"moveit_core", "online_signal_smoothing::SmoothingBaseClass");
95+
smoother_ = smoother_loader_->createUniqueInstance(servo_params_.smoothing_filter_plugin_name);
96+
}
97+
catch (pluginlib::PluginlibException& ex)
98+
{
99+
RCLCPP_ERROR(logger_, "Exception while loading the smoothing plugin '%s': '%s'",
100+
servo_params_.smoothing_filter_plugin_name.c_str(), ex.what());
101+
std::exit(EXIT_FAILURE);
102+
}
103+
104+
// Initialize the smoothing plugin
105+
moveit::core::RobotStatePtr robot_state = planning_scene_monitor_->getStateMonitor()->getCurrentState();
106+
const int num_joints =
107+
robot_state->getJointModelGroup(servo_params_.move_group_name)->getActiveJointModelNames().size();
108+
if (!smoother_->initialize(node_, planning_scene_monitor_->getRobotModel(), num_joints))
109+
{
110+
RCLCPP_ERROR(logger_, "Smoothing plugin could not be initialized");
111+
std::exit(EXIT_FAILURE);
112+
}
113+
>>>>>>> 92654dd1b (Fix severe warning from class loader in servo (#3577))
88114
}
89115

90116
bool Servo::getCommandFrameTransform(Eigen::Isometry3d& transform)

0 commit comments

Comments
 (0)