diff --git a/swiftpro/launch/pro_control.launch b/swiftpro/launch/pro_control.launch
index dfe1cd2..931e9df 100755
--- a/swiftpro/launch/pro_control.launch
+++ b/swiftpro/launch/pro_control.launch
@@ -1,10 +1,15 @@
-
+
+
-
-
-
+
+
+ args="$(port)"
+
+
diff --git a/swiftpro/launch/pro_display.launch b/swiftpro/launch/pro_display.launch
index b4cb9fa..931e9df 100755
--- a/swiftpro/launch/pro_display.launch
+++ b/swiftpro/launch/pro_display.launch
@@ -1,9 +1,14 @@
-
+
+
-
+
+ args="$(port)"
+
diff --git a/swiftpro/launch/swift_control.launch b/swiftpro/launch/swift_control.launch
index c0af20b..4d922ea 100755
--- a/swiftpro/launch/swift_control.launch
+++ b/swiftpro/launch/swift_control.launch
@@ -1,8 +1,15 @@
+
-
+
+ args="$(port)"
+
+
diff --git a/swiftpro/launch/swift_display.launch b/swiftpro/launch/swift_display.launch
index e9fa998..75a8ede 100755
--- a/swiftpro/launch/swift_display.launch
+++ b/swiftpro/launch/swift_display.launch
@@ -1,9 +1,14 @@
+
-
+
+ args="$(port)"
+
diff --git a/swiftpro/src/swiftpro_read_node.cpp b/swiftpro/src/swiftpro_read_node.cpp
index 82bc9c5..5527342 100755
--- a/swiftpro/src/swiftpro_read_node.cpp
+++ b/swiftpro/src/swiftpro_read_node.cpp
@@ -67,16 +67,25 @@ void handlechar(char c)
int main(int argc, char** argv)
{
ros::init(argc, argv, "swiftpro_read_node");
- ros::NodeHandle nh;
+ ros::NodeHandle nh("~");
swiftpro::SwiftproState swiftpro_state;
std_msgs::String result;
+ std::string param;
+ std::string serport;
+
ros::Publisher pub = nh.advertise("SwiftproState_topic", 1);
ros::Rate loop_rate(20);
+ if (nh.getParam("port",param)) {
+ serport.assign(param.c_str());
+ } else {
+ serport="/dev/ttyUSB0";
+ }
+
try
{
- _serial.setPort("/dev/ttyACM0");
+ _serial.setPort(serport);
_serial.setBaudrate(115200);
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
_serial.setTimeout(to);
diff --git a/swiftpro/src/swiftpro_write_node.cpp b/swiftpro/src/swiftpro_write_node.cpp
index dd67ad8..03a7661 100755
--- a/swiftpro/src/swiftpro_write_node.cpp
+++ b/swiftpro/src/swiftpro_write_node.cpp
@@ -161,7 +161,11 @@ void pump_callback(const swiftpro::status& msg)
int main(int argc, char** argv)
{
ros::init(argc, argv, "swiftpro_write_node");
- ros::NodeHandle nh;
+ ros::NodeHandle nh("~");
+
+ std::string param;
+ std::string serport;
+
swiftpro::SwiftproState swiftpro_state;
ros::Subscriber sub1 = nh.subscribe("position_write_topic", 1, position_write_callback);
@@ -172,9 +176,16 @@ int main(int argc, char** argv)
ros::Publisher pub = nh.advertise("SwiftproState_topic", 1);
ros::Rate loop_rate(20);
+ ROS_INFO("Got parameter: %s", param.c_str());
+ if (nh.getParam("port",param)) {
+ serport.assign(param.c_str());
+ } else {
+ serport="/dev/ttyUSB0";
+ }
+
try
{
- _serial.setPort("/dev/ttyACM0");
+ _serial.setPort(serport);
_serial.setBaudrate(115200);
serial::Timeout to = serial::Timeout::simpleTimeout(1000);
_serial.setTimeout(to);