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
GitLab community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
This is an archived project. Repository and other project resources are read-only.
Show more breadcrumbs
CeTI
ROS
ROS Packages
franka_description
Commits
d22123ec
Commit
d22123ec
authored
7 years ago
by
Simon Gabl
Browse files
Options
Downloads
Patches
Plain Diff
Clang format.
parent
60170cda
No related branches found
No related tags found
No related merge requests found
Changes
3
Show whitespace changes
Inline
Side-by-side
Showing
3 changed files
franka_control/src/franka_control_node.cpp
+2
-7
2 additions, 7 deletions
franka_control/src/franka_control_node.cpp
franka_hw/include/franka_hw/franka_hw.h
+12
-6
12 additions, 6 deletions
franka_hw/include/franka_hw/franka_hw.h
franka_hw/src/franka_hw.cpp
+18
-9
18 additions, 9 deletions
franka_hw/src/franka_hw.cpp
with
32 additions
and
22 deletions
franka_control/src/franka_control_node.cpp
+
2
−
7
View file @
d22123ec
...
@@ -95,12 +95,6 @@ int main(int argc, char** argv) {
...
@@ -95,12 +95,6 @@ int main(int argc, char** argv) {
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}},
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}},
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}},
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}},
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}},
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}});
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}},
{{
20.0
,
20.0
,
20.0
,
25.0
,
25.0
,
25.0
}});
robot
.
setCollisionBehavior
(
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}},
{{
100.0
,
100.0
,
100.0
,
100.0
,
100.0
,
100.0
}});
std
::
atomic_bool
has_error
(
false
);
std
::
atomic_bool
has_error
(
false
);
using
std
::
placeholders
::
_1
;
using
std
::
placeholders
::
_1
;
...
@@ -142,7 +136,8 @@ int main(int argc, char** argv) {
...
@@ -142,7 +136,8 @@ int main(int argc, char** argv) {
false
);
false
);
franka
::
Model
model
=
robot
.
loadModel
();
franka
::
Model
model
=
robot
.
loadModel
();
franka_hw
::
FrankaHW
franka_control
(
joint_names
,
arm_id
,
internal_controller
,
rate_limiting
,
cutoff_freq
,
public_node_handle
,
model
);
franka_hw
::
FrankaHW
franka_control
(
joint_names
,
arm_id
,
internal_controller
,
rate_limiting
,
cutoff_freq
,
public_node_handle
,
model
);
// Initialize robot state before loading any controller
// Initialize robot state before loading any controller
franka_control
.
update
(
robot
.
readOnce
());
franka_control
.
update
(
robot
.
readOnce
());
...
...
This diff is collapsed.
Click to expand it.
franka_hw/include/franka_hw/franka_hw.h
+
12
−
6
View file @
d22123ec
...
@@ -48,9 +48,12 @@ class FrankaHW : public hardware_interface::RobotHW {
...
@@ -48,9 +48,12 @@ class FrankaHW : public hardware_interface::RobotHW {
*
*
* @param[in] joint_names An array of joint names being controlled.
* @param[in] joint_names An array of joint names being controlled.
* @param[in] arm_id Unique identifier for the robot being controlled.
* @param[in] arm_id Unique identifier for the robot being controlled.
* @param[in] limit_rate An array of booleans indicating if the rate limiter should be used or not for each interface
* @param[in] limit_rate An array of booleans indicating if the rate limiter should be used or not
* @param[in] internal_controller Internal controller to be used for control loops using only motion generation
* for each interface
* @param[in] cutoff_freq An array of doubles indicating the cutoff frequency for the lowpass applied in each interface
* @param[in] internal_controller Internal controller to be used for control loops using only
* motion generation
* @param[in] cutoff_freq An array of doubles indicating the cutoff frequency for the lowpass
* applied in each interface
* @param[in] node_handle A node handle to get parameters from.
* @param[in] node_handle A node handle to get parameters from.
*/
*/
FrankaHW
(
const
std
::
array
<
std
::
string
,
7
>&
joint_names
,
FrankaHW
(
const
std
::
array
<
std
::
string
,
7
>&
joint_names
,
...
@@ -66,9 +69,12 @@ class FrankaHW : public hardware_interface::RobotHW {
...
@@ -66,9 +69,12 @@ class FrankaHW : public hardware_interface::RobotHW {
* @param[in] joint_names An array of joint names being controlled.
* @param[in] joint_names An array of joint names being controlled.
* @param[in] arm_id Unique identifier for the robot being controlled.
* @param[in] arm_id Unique identifier for the robot being controlled.
* @param[in] node_handle A node handle to get parameters from.
* @param[in] node_handle A node handle to get parameters from.
* @param[in] limit_rate An array of booleans indicating if the rate limiter should be used or not for each interface
* @param[in] limit_rate An array of booleans indicating if the rate limiter should be used or not
* @param[in] internal_controller Internal controller to be used for control loops using only motion generation
* for each interface
* @param[in] cutoff_freq An array of doubles indicating the cutoff frequency for the lowpass applied in each interface
* @param[in] internal_controller Internal controller to be used for control loops using only
* motion generation
* @param[in] cutoff_freq An array of doubles indicating the cutoff frequency for the lowpass
* applied in each interface
* @param[in] model Robot model.
* @param[in] model Robot model.
*/
*/
FrankaHW
(
const
std
::
array
<
std
::
string
,
7
>&
joint_names
,
FrankaHW
(
const
std
::
array
<
std
::
string
,
7
>&
joint_names
,
...
...
This diff is collapsed.
Click to expand it.
franka_hw/src/franka_hw.cpp
+
18
−
9
View file @
d22123ec
...
@@ -275,31 +275,36 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
...
@@ -275,31 +275,36 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
case
ControlMode
::
JointTorque
:
case
ControlMode
::
JointTorque
:
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
};
};
break
;
break
;
case
ControlMode
::
JointPosition
:
case
ControlMode
::
JointPosition
:
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointPositions
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointPositions
>
,
this
,
std
::
cref
(
position_joint_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
0
],
cutoff_freq_
[
0
]);
std
::
cref
(
position_joint_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
0
],
cutoff_freq_
[
0
]);
};
};
break
;
break
;
case
ControlMode
::
JointVelocity
:
case
ControlMode
::
JointVelocity
:
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointVelocities
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointVelocities
>
,
this
,
std
::
cref
(
velocity_joint_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
1
],
cutoff_freq_
[
1
]);
std
::
cref
(
velocity_joint_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
1
],
cutoff_freq_
[
1
]);
};
};
break
;
break
;
case
ControlMode
::
CartesianPose
:
case
ControlMode
::
CartesianPose
:
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianPose
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianPose
>
,
this
,
std
::
cref
(
pose_cartesian_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
2
],
cutoff_freq_
[
2
]);
std
::
cref
(
pose_cartesian_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
2
],
cutoff_freq_
[
2
]);
};
};
break
;
break
;
case
ControlMode
::
CartesianVelocity
:
case
ControlMode
::
CartesianVelocity
:
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
run_function_
=
[
this
](
franka
::
Robot
&
robot
,
Callback
ros_callback
)
{
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianVelocities
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianVelocities
>
,
this
,
std
::
cref
(
velocity_cartesian_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
3
],
cutoff_freq_
[
3
]);
std
::
cref
(
velocity_cartesian_command_
),
ros_callback
,
_1
,
_2
),
internal_controller_
,
limit_rate_
[
3
],
cutoff_freq_
[
3
]);
};
};
break
;
break
;
case
(
ControlMode
::
JointTorque
|
ControlMode
::
JointPosition
):
case
(
ControlMode
::
JointTorque
|
ControlMode
::
JointPosition
):
...
@@ -307,7 +312,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
...
@@ -307,7 +312,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointPositions
>
,
this
,
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointPositions
>
,
this
,
std
::
cref
(
position_joint_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
std
::
cref
(
position_joint_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
};
};
break
;
break
;
case
(
ControlMode
::
JointTorque
|
ControlMode
::
JointVelocity
):
case
(
ControlMode
::
JointTorque
|
ControlMode
::
JointVelocity
):
...
@@ -315,7 +321,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
...
@@ -315,7 +321,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointVelocities
>
,
this
,
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
JointVelocities
>
,
this
,
std
::
cref
(
velocity_joint_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
std
::
cref
(
velocity_joint_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
};
};
break
;
break
;
case
(
ControlMode
::
JointTorque
|
ControlMode
::
CartesianPose
):
case
(
ControlMode
::
JointTorque
|
ControlMode
::
CartesianPose
):
...
@@ -323,7 +330,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
...
@@ -323,7 +330,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianPose
>
,
this
,
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianPose
>
,
this
,
std
::
cref
(
pose_cartesian_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
std
::
cref
(
pose_cartesian_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
};
};
break
;
break
;
case
(
ControlMode
::
JointTorque
|
ControlMode
::
CartesianVelocity
):
case
(
ControlMode
::
JointTorque
|
ControlMode
::
CartesianVelocity
):
...
@@ -331,7 +339,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
...
@@ -331,7 +339,8 @@ bool FrankaHW::prepareSwitch(const std::list<hardware_interface::ControllerInfo>
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
robot
.
control
(
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
Torques
>
,
this
,
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
cref
(
effort_joint_command_
),
ros_callback
,
_1
,
_2
),
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianVelocities
>
,
this
,
std
::
bind
(
&
FrankaHW
::
controlCallback
<
franka
::
CartesianVelocities
>
,
this
,
std
::
cref
(
velocity_cartesian_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
std
::
cref
(
velocity_cartesian_command_
),
ros_callback
,
_1
,
_2
),
limit_rate_
[
4
],
cutoff_freq_
[
4
]);
};
};
break
;
break
;
default
:
default
:
...
...
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