Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
F
franka_description
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Container registry
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Nikhil Ambardar
franka_description
Commits
610c586f
Commit
610c586f
authored
5 years ago
by
Florian Walch
Browse files
Options
Downloads
Patches
Plain Diff
Add rosparam for franka::RealtimeConfig
parent
143129b1
No related branches found
No related tags found
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
CHANGELOG.md
+1
-0
1 addition, 0 deletions
CHANGELOG.md
franka_control/config/franka_control_node.yaml
+2
-0
2 additions, 0 deletions
franka_control/config/franka_control_node.yaml
franka_control/src/franka_control_node.cpp
+15
-2
15 additions, 2 deletions
franka_control/src/franka_control_node.cpp
with
18 additions
and
2 deletions
CHANGELOG.md
+
1
−
0
View file @
610c586f
...
...
@@ -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
...
...
This diff is collapsed.
Click to expand it.
franka_control/config/franka_control_node.yaml
+
2
−
0
View file @
610c586f
...
...
@@ -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
This diff is collapsed.
Click to expand it.
franka_control/src/franka_control_node.cpp
+
15
−
2
View file @
610c586f
...
...
@@ -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
;
}
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Save comment
Cancel
Please
register
or
sign in
to comment