Main Page
Namespaces
Files
File List
bin
example_move_joint.py
Go to the documentation of this file.
1
#!/usr/bin/env python
2
#
3
# Copyright 2019 Shadow Robot Company Ltd.
4
#
5
# This program is free software: you can redistribute it and/or modify it
6
# under the terms of the GNU General Public License as published by the Free
7
# Software Foundation version 2 of the License.
8
#
9
# This program is distributed in the hope that it will be useful, but WITHOUT
10
# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11
# FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12
# more details.
13
#
14
# You should have received a copy of the GNU General Public License along
15
# with this program. If not, see <http://www.gnu.org/licenses/>.
16
17
import
roslib
18
import
rospy
19
from
std_msgs.msg
import
Float64
20
import
math
21
22
rospy.init_node(
'example1'
)
23
24
# Move a joint, send position.
25
# NB Load position controllers first
26
27
# Create publisher for the joints controller
28
ffj3_pub = rospy.Publisher(
29
"/sh_ffj3_muscle_position_controller/command"
, Float64, latch=
True
)
30
31
# Send targets
32
ffj3_pub.publish(0)
33
rospy.sleep(2)
34
ffj3_pub.publish(math.radians(90))
35
rospy.sleep(6)
36
37
# Using explicit message
38
msg =
Float64
()
39
msg.data = 0
40
ffj3_pub.publish(msg)
41
rospy.sleep(2)
example_sendupdate.Float64
Float64
Definition:
example_sendupdate.py:39
sr_edc_muscle_tools
Author(s): Mark Pitchless
autogenerated on Tue Oct 13 2020 04:01:56