Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 4 additions & 4 deletions create_node/nodes/turtlebot_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,7 @@ def start(self):
self.robot.start(self.port, robot_types.ROBOT_TYPES[self.robot_type].baudrate)
break
except serial.serialutil.SerialException as ex:
msg = "Failed to open port %s. Error: %s Please make sure the Create cable is plugged into the computer. \n"%((self.port), ex.message)
msg = "Failed to open port %s. Error: %s Please make sure the Create cable is plugged into the computer. Ensure environment variable is set to TURTLEBOT_BASE=create for Create 1 base, TURTLEBOT_BASE=roomba for Create 2.\n"%((self.port), ex.message)
self._diagnostics.node_status(msg,"error")
if log_once:
log_once = False
Expand Down Expand Up @@ -237,7 +237,7 @@ def cmd_vel(self, msg):

def set_operation_mode(self,req):
if not self.robot.sci:
rospy.logwarn("Create : robot not connected yet, sci not available")
rospy.logwarn("Create : robot not connected yet, sci not available. Check if cable is connected. Incorrect TURTLEBOT_BASE environment variable causing the wrong baudrate to be used is another possible cause. Ensure environment variable is set to TURTLEBOT_BASE=create for Create 1 base, TURTLEBOT_BASE=roomba for Create 2.")
return SetTurtlebotModeResponse(False)

self.operate_mode = req.mode
Expand Down Expand Up @@ -309,7 +309,7 @@ def _set_digital_outputs(self, outputs):

def set_digital_outputs(self,req):
if not self.robot.sci:
raise Exception("Robot not connected, SCI not available")
raise Exception("Robot not connected, SCI not available. Incorrect TURTLEBOT_BASE environment variable causing the wrong baudrate to be used is another possible cause.")

outputs = [req.digital_out_0,req.digital_out_1, req.digital_out_2]
self._set_digital_outputs(outputs)
Expand All @@ -325,7 +325,7 @@ def spin(self):
# state
s = self.sensor_state
odom = Odometry(header=rospy.Header(frame_id=self.odom_frame), child_frame_id=self.base_frame)
js = JointState(name = ["left_wheel_joint", "right_wheel_joint", "front_castor_joint", "back_castor_joint"],
js = JointState(name = ["left_wheel_joint", "right_wheel_joint", "front_castor_joint", "rear_castor_joint"],
position=[0,0,0,0], velocity=[0,0,0,0], effort=[0,0,0,0])

r = rospy.Rate(self.update_rate)
Expand Down