Skip to content
Snippets Groups Projects
Commit 610c586f authored by Florian Walch's avatar Florian Walch
Browse files

Add rosparam for franka::RealtimeConfig

parent 143129b1
No related branches found
No related tags found
No related merge requests found
......@@ -17,6 +17,7 @@ Requires `libfranka` >= 0.5.0
* **BREAKING** Moved `panda_moveit_config` to [`ros-planning`](https://github.com/ros-planning/panda_moveit_config).
* Added support for ROS Melodic Morenia.
* Raised minimum CMake version to 3.4 to match `libfranka`.
* Add rosparam to choose value of `franka::RealtimeConfig`.
## 0.6.0 - 2018-08-08
......
......@@ -13,3 +13,5 @@ rate_limiting: true
cutoff_frequency: 100
# Internal controller for motion generators [joint_impedance|cartesian_impedance]
internal_controller: joint_impedance
# Used to decide whether to enforce realtime mode [enforce|ignore]
realtime_config: enforce
......@@ -78,7 +78,18 @@ int main(int argc, char** argv) {
ROS_ERROR("Invalid or no arm_id parameter provided");
return 1;
}
franka::Robot robot(robot_ip);
std::string realtime_config_param = node_handle.param("realtime_config", std::string("enforce"));
franka::RealtimeConfig realtime_config;
if (realtime_config_param == "enforce") {
realtime_config = franka::RealtimeConfig::kEnforce;
} else if (realtime_config_param == "ignore") {
realtime_config = franka::RealtimeConfig::kIgnore;
} else {
ROS_ERROR("Invalid realtime_config parameter provided. Valid values are 'enforce', 'ignore'.");
return 1;
}
franka::Robot robot(robot_ip, realtime_config);
// Set default collision behavior
robot.setCollisionBehavior(
......@@ -149,7 +160,9 @@ int main(int argc, char** argv) {
} else if (internal_controller == "cartesian_impedance") {
controller_mode = franka::ControllerMode::kCartesianImpedance;
} else {
ROS_WARN("Invalid internal_controller parameter provided, falling back to joint impedance");
ROS_WARN(
"Invalid internal_controller parameter provided, falling back to joint impedance. Valid "
"values are: 'joint_impedance', 'cartesian_impedance'.");
controller_mode = franka::ControllerMode::kJointImpedance;
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment