-
Notifications
You must be signed in to change notification settings - Fork 2
Stm #5
base: develop
Are you sure you want to change the base?
Conversation
Stm must be written as STM |
eurobot_stm/scripts/STM_node.py
Outdated
import itertools | ||
from STM_protocol import STMprotocol | ||
|
||
ODOM_RATE = 40 # Hz |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
move this constant to config yaml file
eurobot_stm/scripts/STM_node.py
Outdated
# Init ROS | ||
rospy.init_node('stm_node', anonymous=True) | ||
# ROS subscribers | ||
rospy.Subscriber("stm_command", String, self.stm_command_callback) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Initialize subscriber in the end of init function
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
May be race condition
eurobot_stm/scripts/STM_node.py
Outdated
super(STMnode, self).__init__(serial_port, baudrate) | ||
self.mutex = Lock() | ||
|
||
self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Change config file to make all constant in meters
eurobot_stm/scripts/STM_node.py
Outdated
|
||
rospy.Timer(rospy.Duration(1. / ODOM_RATE), self.odom_callback) | ||
|
||
def stm_command_callback(self, data): |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Why you remove cmd_id ?
eurobot_stm/scripts/STM_node.py
Outdated
rospy.loginfo('Got response args: '+ str(values)) | ||
return successfully, values | ||
|
||
def odom_callback(self, event): |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
odom callback?
eurobot_stm/scripts/STM_node.py
Outdated
successfully, values = self.send(0x0F, args=None) | ||
if successfully: | ||
self.send_odometry(values) | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Make twist_callback
eurobot_stm/scripts/STM_node.py
Outdated
t.header.stamp = rospy.Time.now() | ||
t.header.frame_id = "secondary_robot_odom" | ||
t.child_frame_id = "secondary_robot" | ||
t.transform.translation.x = values[0] |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Use function from core function to cvt_ros_transform2point
eurobot_stm/scripts/STM_node.py
Outdated
if successfully: | ||
self.send_odometry(values) | ||
|
||
def send_odometry(self, values): |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
rename to publish_odometry
eurobot_stm/scripts/STM_node.py
Outdated
|
||
self.tf2_broad.sendTransform(t) | ||
|
||
t = geometry_msgs.msg.TransformStamped() |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Make function publish_tf
eurobot_stm/scripts/STM_node.py
Outdated
|
||
t = geometry_msgs.msg.TransformStamped() | ||
t.header.stamp = rospy.Time.now() | ||
t.header.frame_id = "secondary_robot" |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Make this as params in config file
eurobot_stm/scripts/STM_node.py
Outdated
import struct | ||
import serial | ||
import itertools | ||
from STM_protocol import STMprotocol |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
test
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Add launch file for stm node
Misha, please, pull my beautiful code again 😀😀😀