Skip to content

Commit

Permalink
Merge pull request #994 from tue-robotics/docstyle-fixes2
Browse files Browse the repository at this point in the history
Fix doc style.
  • Loading branch information
MatthijsBurgh committed Feb 1, 2020
2 parents 73d0af2 + c95094c commit 49b1688
Show file tree
Hide file tree
Showing 50 changed files with 197 additions and 90 deletions.
2 changes: 1 addition & 1 deletion challenge_cleanup/src/challenge_cleanup/clean_inspect.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ def __init__(self, robot, location_des):
"""
Visit all selected locations from the list, and handle the found objects
:param location_des is a designator resolving to a dictionary with fields ... TODO
:param location_des: is a designator resolving to a dictionary with fields ... TODO
"""

smach.StateMachine.__init__(self, outcomes=['done'])
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ def color_map(N=256, normalized=False):
:param N : int amount of colors to generate
:param normalized: bool indicating range of each channel: float32 in [0, 1] or int in [0, 255]
:return a numpy.array of shape (N, 3) with a row for each color and each row is [R,G,B]
:return: a numpy.array of shape (N, 3) with a row for each color and each row is [R,G,B]
"""

def bitget(byteval, idx):
Expand Down
2 changes: 1 addition & 1 deletion challenge_final/src/challenge_final/find_people.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ def color_map(N=256, normalized=False):
:param N : int amount of colors to generate
:param normalized: bool indicating range of each channel: float32 in [0, 1] or int in [0, 255]
:return a numpy.array of shape (N, 3) with a row for each color and each row is [R,G,B]
:return: a numpy.array of shape (N, 3) with a row for each color and each row is [R,G,B]
"""

def bitget(byteval, idx):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ def color_map(N=256, normalized=False):
:param N : int amount of colors to generate
:param normalized: bool indicating range of each channel: float32 in [0, 1] or int in [0, 255]
:return a numpy.array of shape (N, 3) with a row for each color and each row is [R,G,B]
:return: a numpy.array of shape (N, 3) with a row for each color and each row is [R,G,B]
"""

def bitget(byteval, idx):
Expand Down
10 changes: 7 additions & 3 deletions challenge_manipulation/src/manipulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,13 @@ def execute(self, userdata=None):


class ForceRotate(smach.State):
""" Force forth and back. If a timeout is exceeded, we won't do this anymore """
"""
Force forth and back. If a timeout is exceeded, we won't do this anymore
State is exited with
- done: rotated back and forth
- timedout: this takes too long
"""

def __init__(self, robot, vth, duration, timeout):
"""
Expand All @@ -167,8 +173,6 @@ def __init__(self, robot, vth, duration, timeout):
:param vth: yaw-velocity
:param duration: float indicating how long to drive
:param timeout: after this, timedout is returned
:return done: rotated back and forth
:return timedout: this takes too long
"""
smach.State.__init__(self, outcomes=['done', 'timedout'])
self._robot = robot
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,7 @@ def execute(self, userdata=None):
class PresentationMachine(smach.StateMachine):
def __init__(self, robot, language='nl'):
""" Contains the Initialize state and the Presentation state
:param robot: Robot to use
:return:
"""
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ def __init__(self, robot,
guest_name_des, guest_drink_des):
"""
Learn what a guest looks like and what his/her favourite drink is
:param robot: Robot that should execute this state
:param door_waypoint: Entity-designator resolving to a waypoint Where are guests expected to come in
:param guest_ent_des: Entity of the guest
Expand Down
8 changes: 4 additions & 4 deletions challenge_restaurant/src/challenge_restaurant/take_orders.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ def __init__(self, robot, entity_designator, orders):
:param robot: robot object
:param orders: Python dict in which the orders will be stored
:return:
succeeded: understood correctly
failed: didn't hear anything or exceeded maximum number of tries
misunderstood: misunderstood, might try again
:return: Result of taking orders:
- succeeded: understood correctly
- failed: didn't hear anything or exceeded maximum number of tries
- misunderstood: misunderstood, might try again
"""
smach.State.__init__(self, outcomes=['succeeded', 'failed'])

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ def __init__(self, robot, operator_name, drink_designator,
# type: (Robot, str, VariableDesignator) -> None
"""
Initialization method
:param robot: robot api object
:param operator_name: name with which the operator will be stored in image recognition module
:param drink_designator: (VariableDesignator) in which the drink to fetch is stored
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ def __init__(self, robot, drink_designator, available_drinks_designator, unavail
# type (Robot, VariableDesignator) -> None
"""
Initialization method
:param robot: robot api object
:param drink_designator: (VariableDesignator) in which the drink to fetch is stored
:param available_drinks_designator: (VariableDesignator) in which the available drinks are stored
Expand Down Expand Up @@ -131,6 +132,7 @@ def __init__(self, robot, operator_name, drink_designator, available_drinks_desi
# type (Robot, VariableDesignator) -> None
"""
Initialization method
:param robot: robot api object
:param operator_name: (EntityDesignator) in which the operator's name is stored
:param drink_designator: (VariableDesignator) in which the drink to fetch is stored
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ def __init__(self, robot, bar_designator, room_id, room_designator,
objects_list_des, unav_drink_des, name_options, objects):
"""
Initialization method
:param robot: robot api object
:param bar_designator: (EntityDesignator) in which the bar location is stored
:param room_id: room ID from challenge knowledge
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,7 @@ def __init__(self, robot):
# type: (Robot) -> str
"""
Initialization method
:param robot: robot api object
"""

Expand Down
2 changes: 2 additions & 0 deletions challenge_spr/src/challenge_spr_states/detect.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ def execute(self, userdata=None):
def recognize(self, tries=3):
"""
Recognize people. Takes multiple images and takes the try with the most faces
:param tries: number of tries
:type tries: int
:return: list of face properties
Expand Down Expand Up @@ -90,6 +91,7 @@ def recognize(self, tries=3):
def describe_crowd(self, detections):
"""
Conversion from individual face properties to crowd properties
:param detections: list of face properties
:type detections: list[image_recognition_msgs/FaceProperties]
:return: crowd properties
Expand Down
5 changes: 5 additions & 0 deletions robot_skills/src/robot_skills/api.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ class Api(RobotPart):
def __init__(self, robot_name, tf_listener, pre_hook=None, post_hook=None):
"""
constructor
:param robot_name: robot_name
:param tf_listener: tf_server.TFClient()
:param pre_hook: callable function to execute before a query call, i.e. to set light color
Expand All @@ -35,6 +36,7 @@ def __init__(self, robot_name, tf_listener, pre_hook=None, post_hook=None):
def query(self, description, grammar, target, timeout=10):
"""
Perform a HMI query, returns a HMIResult
:param description: text describing the query
:param grammar: string with the grammar to load
:param target: string identifying the target of the grammar to recognize
Expand All @@ -60,6 +62,7 @@ def query(self, description, grammar, target, timeout=10):
def _show_image(self, msg, seconds=5.0):
"""
Show an image on the HMI display interface
:param msg: CompressedImage to display
:param seconds: How many seconds you would like to display the image on the screen
"""
Expand All @@ -69,6 +72,7 @@ def _show_image(self, msg, seconds=5.0):
def show_image(self, path_to_image, seconds=5.0):
"""
Show an image on the HMI display interface
:param path_to_image: Absolute path to image file
:param seconds: How many seconds you would like to display the image on the screen
"""
Expand All @@ -78,6 +82,7 @@ def show_image(self, path_to_image, seconds=5.0):
def show_image_from_msg(self, msg, seconds=5.0):
"""
Show an image on the HMI display interface
:param msg: rgb msg
:param seconds: How many seconds you would like to display the image on the screen
"""
Expand Down
30 changes: 19 additions & 11 deletions robot_skills/src/robot_skills/arms.py
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,7 @@ def has_gripper_type(self, gripper_type=None):
def send_gripper_goal(self, state, timeout=5.0, gripper_type=None, max_torque=0.1):
"""
Tell the gripper to perform a motion.
:param state: New state of the gripper.
:type state: str (GripperState)
:param timeout: Amount of time available to reach the goal, default is 5
Expand Down Expand Up @@ -334,6 +335,7 @@ class Arm(RobotPart):
def __init__(self, robot_name, tf_listener, get_joint_states, side):
"""
constructor
:param robot_name: robot_name
:param tf_listener: tf_server.TFClient()
:param get_joint_states: get_joint_states function for getting the last joint states
Expand Down Expand Up @@ -588,8 +590,8 @@ def send_joint_goal(self, configuration, timeout=5.0, max_joint_vel=0.7):

def send_joint_trajectory(self, configuration, timeout=5.0, max_joint_vel=0.7):
"""
Send a named joint trajectory (sequence of poses) defined in the default_trajectories to
the arm
Send a named joint trajectory (sequence of poses) defined in the default_trajectories to the arm
:param configuration:(str) name of configuration, configuration should be loaded as parameter
:param timeout:(secs) timeout in seconds
:param max_joint_vel:(int,float,[int]) speed the robot can have when getting to the desired configuration
Expand All @@ -606,6 +608,7 @@ def send_joint_trajectory(self, configuration, timeout=5.0, max_joint_vel=0.7):
def reset(self, timeout=0.0):
"""
Put the arm into the 'reset' pose
:param timeout: timeout in seconds
:return: True or False
"""
Expand All @@ -615,6 +618,7 @@ def reset(self, timeout=0.0):
def occupied_by(self):
"""
The 'occupied_by' property will return the current entity that is in the gripper of this arm.
:return: robot_skills.util.entity, ED entity
"""

Expand All @@ -624,6 +628,7 @@ def occupied_by(self):
def occupied_by(self, value):
"""
Set the entity which occupies the arm.
:param value: robot_skills.util.entity, ED entity
:return: no return
"""
Expand All @@ -632,6 +637,7 @@ def occupied_by(self, value):
def send_gripper_goal(self, state, timeout=5.0, max_torque=0.1):
"""
Send a GripperCommand to the gripper of this arm and wait for finishing
:param state: open or close
:type state: str (GripperState)
:param timeout: timeout in seconds; timeout of 0.0 is not allowed
Expand Down Expand Up @@ -715,13 +721,14 @@ def _send_joint_trajectory(self, joints_references, max_joint_vel=0.7, timeout=r
If timeout is defined, it will wait for timeout*len(joints_reference) seconds for the
completion of the actionlib goal. It will return True as soon as possible when the goal
succeeded. On timeout, it will return False.
:param joints_references:[str] list of joint configurations,
which should be a list of the length equal to the number of joints to be moved
which should be a list of the length equal to the number of joints to be moved
:param max_joint_vel:(int,float,[int], [float]) speed the robot can have when getting to the desired
configuration. A single value can be given, which will be used for all joints, or a list of values can be given
in which the order has to agree with the joints according to the joints_references.
configuration. A single value can be given, which will be used for all joints, or a list of values can be given
in which the order has to agree with the joints according to the joints_references.
:param timeout:(secs) timeout for each joint configuration in rospy.Duration(seconds); timeout of 0.0 is not
allowed
allowed
:return: True or False
"""
if not joints_references:
Expand Down Expand Up @@ -781,11 +788,11 @@ def _send_joint_trajectory(self, joints_references, max_joint_vel=0.7, timeout=r
def wait_for_motion_done(self, timeout=10.0, cancel=False):
"""
Waits until all action clients are done
:param timeout: timeout in seconds; in case 0.0, no sensible output is provided, just False
:param cancel: bool specifying whether goals should be cancelled
if timeout is exceeded
:return bool indicates whether motion was done (True if reached,
False otherwise)
if timeout is exceeded
:return: bool indicates whether motion was done (True if reached, False otherwise)
"""
# rospy.loginfo('Waiting for ac_joint_traj')
starttime = rospy.Time.now()
Expand Down Expand Up @@ -889,9 +896,10 @@ def __repr__(self):
class ForceSensingArm(Arm):
def __init__(self, robot_name, tf_listener, get_joint_states, side):
"""
constructor
:todo: Make the Arm class similar to the robot, such that it can be composed from parts
constructor
:param robot_name: robot_name
:param tf_listener: tf_server.TFClient()
:param get_joint_states: get_joint_states function for getting the last joint states
Expand All @@ -905,7 +913,7 @@ def move_down_until_force_sensor_edge_up(self, timeout=10, retract_distance=0.01
"""
Move down the arm (hero specific, only joint arm_lift_joint) until the force sensor detects an edge up
A force_sensor.TimeOutException will be raised if no edge up is detected within timeout
A 'force_sensor.TimeOutException' will be raised if no edge up is detected within timeout
:param timeout: Max duration for edge up detection
:param retract_distance: How much to retract if we have reached a surface
Expand Down
5 changes: 3 additions & 2 deletions robot_skills/src/robot_skills/base.py
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ def getPlan(self, position_constraint):
:param position_constraint: (PositionConstraint)
:return: list(PoseStamped). N.B.: If No path was found, this list is empty. If the planner service fails,
'None' is returned.
'None' is returned.
"""

self._position_constraint = position_constraint
Expand Down Expand Up @@ -179,7 +179,7 @@ def wait_for_connections(self, timeout, log_failing_connections=True):
:param timeout: timeout in seconds
:param log_failing_connections: (bool) whether to log errors if not connected. This is useful when checking
multiple robot parts in a loop
multiple robot parts in a loop
:return: bool indicating whether all connections are connected
"""
return self.global_planner.wait_for_connections(
Expand Down Expand Up @@ -246,6 +246,7 @@ def _abs_max(value, max_value):

def get_location(self):
""" Returns a FrameStamped with the robot pose
:return: FrameStamped with robot pose
"""
return get_location(self.robot_name, self.tf_listener)
Expand Down
2 changes: 1 addition & 1 deletion robot_skills/src/robot_skills/ebutton.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ def __init__(self, robot_name, tf_listener, topic=None):
:param robot_name: (str) string indicates the robot name
:param tf_listener: (tf.Listener) (default argument for robot parts)
:param topic: (str) fully qualified topic (optional).
If not provided, "/<robot_name>/emergency_switch" will be used.
If not provided, "/<robot_name>/emergency_switch" will be used.
"""
super(EButton, self).__init__(robot_name=robot_name, tf_listener=tf_listener)

Expand Down
3 changes: 3 additions & 0 deletions robot_skills/src/robot_skills/force_sensor.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,14 @@ def _wrench_callback(self, msg):
# type: (WrenchStamped) -> None
"""
Process a WrenchStamped-message to determine if the norm(force) goes over the limit
:param msg: WrenchStamped to see if it goes over self.force_norm_threshold
:return: None but sets self.edge_up
"""
def _detect_edge_up(calibrated_msg, msg):
"""
Determine if the difference between calibrated_msg and msg is larger than self._force_norm_threshold
:param calibrated_msg: Reference message
:param msg: Comparision message, to be compared with the reference message
:return: bool if the difference is larger than the threshold.
Expand All @@ -57,6 +59,7 @@ def _norm(v):
def wait_for_edge_up(self, timeout=10.0):
"""
Returns if an edge up event is detected. Will raise a TimeOutException if no edge up is detected within timeout.
:param timeout: Edge up wait patience
"""
self._edge_up = False
Expand Down
2 changes: 2 additions & 0 deletions robot_skills/src/robot_skills/get_robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@
def get_robot_from_argv(index, default_robot_name="hero"):
"""
Construct a robot from the name given in the command-line or from the default robot name.
:param index: Index in the command-line arguments where a robot name may be available.
:param default_robot_name: Name of the robot to use if the command line did not contain a name.
:return: The constructed robot.
Expand All @@ -38,6 +39,7 @@ def get_robot_from_argv(index, default_robot_name="hero"):
def get_robot(name):
"""
Constructs a robot (api) object based on the provided name
:param name: (str) robot name
:return: (Robot)
:raises: RuntimeError
Expand Down
4 changes: 2 additions & 2 deletions robot_skills/src/robot_skills/hero.py
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ def move_to_inspect_pose(self, inspect_target):
This poses the robot for an inspect.
:param inspect_target: kdl.Frame with the pose of the entity to be inspected.
:return result: boolean, false if something went wrong.
:return: boolean, false if something went wrong.
"""
# calculate the arm_lift_link which must be sent
z_over = 0.4 # height the robot should look over the surface
Expand Down Expand Up @@ -100,7 +100,7 @@ def move_to_hmi_pose(self):
"""
This poses the robot for conversations.
:return None
:return: None
"""
arm = self.get_arm()

Expand Down

0 comments on commit 49b1688

Please sign in to comment.