Main Page
Namespaces
Classes
Files
File List
scripts
sample
100k_1m_connection.py
Go to the documentation of this file.
1
#!/usr/bin/env python
2
import
roslib
3
roslib.load_manifest(
'mini_maxwell'
)
4
import
rospy
5
import
sys
6
import
random
7
import
os
8
9
import
rospkg
10
rospack = rospkg.RosPack()
11
sys.path.append(rospack.get_path(
'mini_maxwell'
) +
"/scripts"
)
12
13
from
mm2client
import
*
14
from
ros_client
import
MMClient
15
from
dynamic_reconfigure.server
import
Server
as
DynamicReconfigureServer
16
from
mini_maxwell.cfg
import
RosClientConfig
as
ConfigType
17
18
class
MMSwitchingConnection
(
MMClient
):
19
def
__init__
(self):
20
self.
use_A
=
True
21
22
self.
rate_limit_A
= 1000 * 1000
#1Mbps
23
self.
rate_limit_B
= 100 * 1000
#100kbps
24
self.
round_trip_A
= 0
25
self.
round_trip_B
= 0
26
27
rospy.set_param(
'~rate_limit'
, self.
rate_limit_A
)
28
rospy.set_param(
'~round_trip'
, self.
round_trip_A
)
29
30
rospy.Timer(rospy.Duration(10), self.
changeConnection
)
31
32
MMClient.__init__(self)
33
34
def
changeConnection
(self, event):
35
self.
use_A
=
not
self.
use_A
36
if
self.
use_A
:
37
self.
rate_limit
= self.
rate_limit_A
38
self.
round_trip
= self.
round_trip_A
39
else
:
40
self.
rate_limit
= self.
rate_limit_B
41
self.
round_trip
= self.
round_trip_B
42
self.
updateMM
()
43
44
45
if
__name__ ==
'__main__'
:
46
rospy.init_node(
'mini_maxwell_switching_connection'
)
47
48
try
:
49
mmc =
MMSwitchingConnection
()
50
except
rospy.ROSInterruptException:
pass
100k_1m_connection.MMSwitchingConnection.rate_limit_B
rate_limit_B
Definition:
100k_1m_connection.py:23
100k_1m_connection.MMSwitchingConnection.changeConnection
def changeConnection(self, event)
Definition:
100k_1m_connection.py:34
ros_client.MMClient
Definition:
ros_client.py:11
100k_1m_connection.MMSwitchingConnection
Definition:
100k_1m_connection.py:18
100k_1m_connection.MMSwitchingConnection.use_A
use_A
Definition:
100k_1m_connection.py:20
100k_1m_connection.MMSwitchingConnection.round_trip_A
round_trip_A
Definition:
100k_1m_connection.py:24
100k_1m_connection.MMSwitchingConnection.round_trip_B
round_trip_B
Definition:
100k_1m_connection.py:25
ros_client.MMClient.rate_limit
rate_limit
Definition:
ros_client.py:27
100k_1m_connection.MMSwitchingConnection.__init__
def __init__(self)
Definition:
100k_1m_connection.py:19
ros_client.MMClient.round_trip
round_trip
Definition:
ros_client.py:26
ros_client.MMClient.updateMM
def updateMM(self)
Definition:
ros_client.py:43
100k_1m_connection.MMSwitchingConnection.rate_limit_A
rate_limit_A
Definition:
100k_1m_connection.py:22
mini_maxwell
Author(s): Yusuke Furuta
autogenerated on Wed Jul 10 2019 03:47:09