Skip to content
GitLab
Explore
Sign in
Register
Primary navigation
Search or go to…
Project
P
panda_simulation
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
This is an archived project. Repository and other project resources are read-only.
Show more breadcrumbs
CeTI
ROS
ROS Packages
panda_simulation
Commits
0538dae6
Commit
0538dae6
authored
4 years ago
by
Johannes Mey
Browse files
Options
Downloads
Patches
Plain Diff
align names with ros package
parent
c479a586
Branches
Branches containing commit
Tags
0.3.4
Tags containing commit
No related merge requests found
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
config/panda_control.yaml
+2
-1
2 additions, 1 deletion
config/panda_control.yaml
launch/simulation.launch
+2
-3
2 additions, 3 deletions
launch/simulation.launch
src/robot_state_initializer.cpp
+4
-4
4 additions, 4 deletions
src/robot_state_initializer.cpp
with
8 additions
and
8 deletions
config/panda_control.yaml
+
2
−
1
View file @
0538dae6
...
@@ -3,7 +3,7 @@
...
@@ -3,7 +3,7 @@
type
:
joint_state_controller/JointStateController
type
:
joint_state_controller/JointStateController
publish_rate
:
100
publish_rate
:
100
p
anda_arm
_controller
:
p
osition_joint_trajectory
_controller
:
type
:
position_controllers/JointTrajectoryController
type
:
position_controllers/JointTrajectoryController
joints
:
joints
:
-
panda_joint1
-
panda_joint1
...
@@ -26,6 +26,7 @@
...
@@ -26,6 +26,7 @@
-
panda_finger_joint2
-
panda_finger_joint2
state_publish_rate
:
25
state_publish_rate
:
25
joint_position_controller
:
joint_position_controller
:
type
:
panda_simulation/JointPositionController
type
:
panda_simulation/JointPositionController
arm_id
:
panda
arm_id
:
panda
...
...
This diff is collapsed.
Click to expand it.
launch/simulation.launch
+
2
−
3
View file @
0538dae6
...
@@ -9,9 +9,8 @@
...
@@ -9,9 +9,8 @@
<arg name="load_gripper" default="true" />
<arg name="load_gripper" default="true" />
<!-- don't include franka_control, but include the controller stuff from there -->
<!-- don't include franka_control, but include the controller stuff from there -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" />
<param name="robot_description" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm_hand.urdf.xacro'" if="$(arg load_gripper)" />
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find franka_description)/robots/panda_arm.urdf.xacro'" unless="$(arg load_gripper)" />
<param name="robot_description" command="$(find xacro)/xacro '$(find franka_description)/robots/panda_arm.urdf.xacro'" unless="$(arg load_gripper)" />
<rosparam command="load" file="$(find franka_control)/config/default_controllers.yaml" />
<!--launch GAZEBO with own world configuration -->
<!--launch GAZEBO with own world configuration -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<include file="$(find gazebo_ros)/launch/empty_world.launch">
...
...
This diff is collapsed.
Click to expand it.
src/robot_state_initializer.cpp
+
4
−
4
View file @
0538dae6
...
@@ -62,11 +62,11 @@ int main(int argc, char **argv) {
...
@@ -62,11 +62,11 @@ int main(int argc, char **argv) {
srv_switch_controller
.
request
.
start_controllers
=
start_controllers
;
srv_switch_controller
.
request
.
start_controllers
=
start_controllers
;
if
(
switch_controller_client
.
call
(
srv_switch_controller
))
{
if
(
switch_controller_client
.
call
(
srv_switch_controller
))
{
ROS_INFO_STREAM
(
"Success switching controllers from "
<<
stream_st
op
_controllers
.
str
()
<<
" to "
ROS_INFO_STREAM
(
"Success switching controllers from "
<<
stream_st
art
_controllers
.
str
()
<<
" to "
<<
stream_st
art
_controllers
.
str
());
<<
stream_st
op
_controllers
.
str
());
}
else
{
}
else
{
ROS_WARN_STREAM
(
"Error switching controllers from "
<<
stream_st
op
_controllers
.
str
()
<<
" to "
ROS_WARN_STREAM
(
"Error switching controllers from "
<<
stream_st
art
_controllers
.
str
()
<<
" to "
<<
stream_st
art
_controllers
.
str
());
<<
stream_st
op
_controllers
.
str
());
return
-
1
;
return
-
1
;
}
}
...
...
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