Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

documentation (docstrings) in python #2804

Open
wants to merge 6 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
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
2 changes: 2 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
* Added documentation in Python.

## CARLA 0.9.9

* Introduced hybrid mode for Traffic Manager
Expand Down
79 changes: 79 additions & 0 deletions PythonAPI/carla/generate_type_hints.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,79 @@
import glob
import re
import sys
from typing import List, Any

import yaml


def safe_list(obj: Any) -> List:
if obj is None:
return []
return obj


def get_docstring(doc_file: str) -> dict:
docstrings = dict()

with open(doc_file, 'r') as yaml_file:
documentations = yaml.safe_load(yaml_file)

for documentation in documentations:
for class_doc in documentation.get('classes', []):
docstrings[class_doc['class_name']] = class_doc['doc']
for method in class_doc.get('methods', []):
params = []
details = method.get('doc', '')
for param in safe_list(method.get('params', [])):
details += "\t@param " + str(param['param_name']) + ": " + str(param.get('doc', ''))
param_sig = str(param['param_name']) + ": " + str(param.get('type', None))
if param.get('default', None):
param_sig += " = " + str(param['default'])
params.append(param_sig)

details += "\t@return: " + str(method.get('return', None))
signature = str(method['def_name']) + "(" + str(', '.join(params)) + ") -> " + str(method.get('return', None)) + "\n\n"
docstrings[str(class_doc["class_name"]) + "." + str(method["def_name"])] = signature + details

for instance_variable in safe_list(class_doc.get('instance_variables', [])):
if instance_variable.get('doc', None):
docstrings[str(class_doc["class_name"]) + "." + str(instance_variable["var_name"])] = str(instance_variable.get('type', None)) + ": " + str(instance_variable['doc'])

return docstrings


def escape(line: str) -> str:
return line.replace('\\', '\\\\').replace('\n', r'\n').replace('"', '\\"')


def substitute(source_file: str, docstrings: dict) -> None:
with open(source_file) as input_file:
lines = input_file.readlines()

output_data = []

pattern = re.compile(r'@DocString\((.+?)\)')
for line in lines:
for match in pattern.finditer(line):
docstring = docstrings.get(match.group(1), None)
if docstring is None:
docstring = "no documentation available"
line = line.replace(match.group(0), escape(docstring))
output_data.append(line)

with open(source_file, 'w') as output_file:
for item in output_data:
output_file.write(item)


if __name__ == '__main__':
doc_files = glob.glob(sys.argv[1]) # carla/PythonAPI/docs/*.yml
docstrings = {}
for doc_file in doc_files:
new_docs = get_docstring(doc_file)
docstrings = {**docstrings, **new_docs}

source_files = glob.glob(sys.argv[2]) # carla/PythonAPI/carla/source/libcarla_template/*.cpp
for source_file in source_files:
substitute(source_file, docstrings)

104 changes: 52 additions & 52 deletions PythonAPI/carla/source/libcarla/Actor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,31 +63,31 @@ void export_actor() {

class_<cc::Actor, boost::noncopyable, boost::shared_ptr<cc::Actor>>("Actor", no_init)
// work-around, force return copy to resolve Actor instead of ActorState.
.add_property("id", CALL_RETURNING_COPY(cc::Actor, GetId))
.add_property("type_id", CALL_RETURNING_COPY(cc::Actor, GetTypeId))
.add_property("parent", CALL_RETURNING_COPY(cc::Actor, GetParent))
.add_property("semantic_tags", &GetSemanticTags)
.add_property("is_alive", CALL_RETURNING_COPY(cc::Actor, IsAlive))
.add_property("id", CALL_RETURNING_COPY(cc::Actor, GetId), "@DocString(Actor.id)")
.add_property("type_id", CALL_RETURNING_COPY(cc::Actor, GetTypeId), "@DocString(Actor.type_id)")
.add_property("parent", CALL_RETURNING_COPY(cc::Actor, GetParent), "@DocString(Actor.parent)")
.add_property("semantic_tags", &GetSemanticTags, "@DocString(Actor.semantic_tags)")
.add_property("is_alive", CALL_RETURNING_COPY(cc::Actor, IsAlive), "@DocString(Actor.is_alive)")
.add_property("attributes", +[] (const cc::Actor &self) {
boost::python::dict atttribute_dict;
for (auto &&attribute_value : self.GetAttributes()) {
atttribute_dict[attribute_value.GetId()] = attribute_value.GetValue();
}
return atttribute_dict;
})
.def("get_world", CALL_RETURNING_COPY(cc::Actor, GetWorld))
.def("get_location", &cc::Actor::GetLocation)
.def("get_transform", &cc::Actor::GetTransform)
.def("get_velocity", &cc::Actor::GetVelocity)
.def("get_angular_velocity", &cc::Actor::GetAngularVelocity)
.def("get_acceleration", &cc::Actor::GetAcceleration)
.def("set_location", &cc::Actor::SetLocation, (arg("location")))
.def("set_transform", &cc::Actor::SetTransform, (arg("transform")))
.def("set_velocity", &cc::Actor::SetVelocity, (arg("vector")))
.def("set_angular_velocity", &cc::Actor::SetAngularVelocity, (arg("vector")))
.def("add_impulse", &cc::Actor::AddImpulse, (arg("vector")))
.def("set_simulate_physics", &cc::Actor::SetSimulatePhysics, (arg("enabled") = true))
.def("destroy", CALL_WITHOUT_GIL(cc::Actor, Destroy))
}, "@DocString(Actor.attributes)")
.def("get_world", CALL_RETURNING_COPY(cc::Actor, GetWorld), "@DocString(Actor.get_world)")
.def("get_location", &cc::Actor::GetLocation, "@DocString(Actor.get_location)")
.def("get_transform", &cc::Actor::GetTransform, "@DocString(Actor.get_transform)")
.def("get_velocity", &cc::Actor::GetVelocity, "@DocString(Actor.get_velocity)")
.def("get_angular_velocity", &cc::Actor::GetAngularVelocity, "@DocString(Actor.get_angular_velocity)")
.def("get_acceleration", &cc::Actor::GetAcceleration, "@DocString(Actor.get_acceleration)")
.def("set_location", &cc::Actor::SetLocation, (arg("location")), "@DocString(Actor.set_location)")
.def("set_transform", &cc::Actor::SetTransform, (arg("transform")), "@DocString(Actor.set_transform)")
.def("set_velocity", &cc::Actor::SetVelocity, (arg("vector")), "@DocString(Actor.set_velocity)")
.def("set_angular_velocity", &cc::Actor::SetAngularVelocity, (arg("vector")), "@DocString(Actor.set_angular_velocity)")
.def("add_impulse", &cc::Actor::AddImpulse, (arg("vector")), "@DocString(Actor.add_impulse)")
.def("set_simulate_physics", &cc::Actor::SetSimulatePhysics, (arg("enabled") = true), "@DocString(Actor.set_simulate_physics)")
.def("destroy", CALL_WITHOUT_GIL(cc::Actor, Destroy), "@DocString(Actor.destroy)")
.def(self_ns::str(self_ns::self))
;

Expand All @@ -110,40 +110,40 @@ void export_actor() {
class_<cc::Vehicle, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::Vehicle>>("Vehicle",
no_init)
.add_property("bounding_box", CALL_RETURNING_COPY(cc::Vehicle, GetBoundingBox))
.def("apply_control", &cc::Vehicle::ApplyControl, (arg("control")))
.def("get_control", &cc::Vehicle::GetControl)
.def("set_light_state", &cc::Vehicle::SetLightState, (arg("light_state")))
.def("get_light_state", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetLightState))
.def("apply_physics_control", &cc::Vehicle::ApplyPhysicsControl, (arg("physics_control")))
.def("get_physics_control", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetPhysicsControl))
.def("set_autopilot", CALL_WITHOUT_GIL_2(cc::Vehicle, SetAutopilot, bool, uint16_t), (arg("enabled") = true, arg("tm_port") = TM_DEFAULT_PORT))
.def("get_speed_limit", &cc::Vehicle::GetSpeedLimit)
.def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState)
.def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight)
.def("get_traffic_light", &cc::Vehicle::GetTrafficLight)
.def("apply_control", &cc::Vehicle::ApplyControl, (arg("control")), "@DocString(Vehicle.apply_control)")
.def("get_control", &cc::Vehicle::GetControl, "@DocString(Vehicle.get_control)")
.def("set_light_state", &cc::Vehicle::SetLightState, (arg("light_state")), "@DocString(Vehicle.set_light_state)")
.def("get_light_state", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetLightState), "@DocString(Vehicle.get_light_state)")
.def("apply_physics_control", &cc::Vehicle::ApplyPhysicsControl, (arg("physics_control")), "@DocString(Vehicle.apply_physics_control)")
.def("get_physics_control", CONST_CALL_WITHOUT_GIL(cc::Vehicle, GetPhysicsControl), "@DocString(Vehicle.get_physics_control)")
.def("set_autopilot", CALL_WITHOUT_GIL_2(cc::Vehicle, SetAutopilot, bool, uint16_t), (arg("enabled") = true, arg("tm_port") = TM_DEFAULT_PORT), "@DocString(Vehicle.set_autopilot)")
.def("get_speed_limit", &cc::Vehicle::GetSpeedLimit, "@DocString(Vehicle.get_speed_limit)")
.def("get_traffic_light_state", &cc::Vehicle::GetTrafficLightState, "@DocString(Vehicle.get_traffic_light_state)")
.def("is_at_traffic_light", &cc::Vehicle::IsAtTrafficLight, "@DocString(Vehicle.is_at_traffic_light)")
.def("get_traffic_light", &cc::Vehicle::GetTrafficLight, "@DocString(Vehicle.get_traffic_light)")
.def(self_ns::str(self_ns::self))
;

class_<cc::Walker, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::Walker>>("Walker", no_init)
.add_property("bounding_box", CALL_RETURNING_COPY(cc::Walker, GetBoundingBox))
.def("apply_control", &ApplyControl<cr::WalkerControl>, (arg("control")))
.def("apply_control", &ApplyControl<cr::WalkerBoneControl>, (arg("control")))
.def("get_control", &cc::Walker::GetWalkerControl)
.def("apply_control", &ApplyControl<cr::WalkerControl>, (arg("control")), "@DocString(Walker.apply_control)")
.def("apply_control", &ApplyControl<cr::WalkerBoneControl>, (arg("control")), "@DocString(Walker.apply_control)")
.def("get_control", &cc::Walker::GetWalkerControl, "@DocString(Walker.get_control)")
.def(self_ns::str(self_ns::self))
;

class_<cc::WalkerAIController, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::WalkerAIController>>("WalkerAIController", no_init)
.def("start", &cc::WalkerAIController::Start)
.def("stop", &cc::WalkerAIController::Stop)
.def("go_to_location", &cc::WalkerAIController::GoToLocation, (arg("destination")))
.def("set_max_speed", &cc::WalkerAIController::SetMaxSpeed, (arg("speed")))
.def("start", &cc::WalkerAIController::Start, "@DocString(WalkerAIController.start)")
.def("stop", &cc::WalkerAIController::Stop, "@DocString(WalkerAIController.stop)")
.def("go_to_location", &cc::WalkerAIController::GoToLocation, (arg("destination")), "@DocString(WalkerAIController.go_to_location)")
.def("set_max_speed", &cc::WalkerAIController::SetMaxSpeed, (arg("speed")), "@DocString(WalkerAIController.set_max_speed)")
.def(self_ns::str(self_ns::self))
;

class_<cc::TrafficSign, bases<cc::Actor>, boost::noncopyable, boost::shared_ptr<cc::TrafficSign>>(
"TrafficSign",
no_init)
.add_property("trigger_volume", CALL_RETURNING_COPY(cc::TrafficSign, GetTriggerVolume))
.add_property("trigger_volume", CALL_RETURNING_COPY(cc::TrafficSign, GetTriggerVolume), "@DocString(TrafficSign.trigger_volume)")
;

enum_<cr::TrafficLightState>("TrafficLightState")
Expand All @@ -157,20 +157,20 @@ void export_actor() {
class_<cc::TrafficLight, bases<cc::TrafficSign>, boost::noncopyable, boost::shared_ptr<cc::TrafficLight>>(
"TrafficLight",
no_init)
.add_property("state", &cc::TrafficLight::GetState)
.def("set_state", &cc::TrafficLight::SetState, (arg("state")))
.def("get_state", &cc::TrafficLight::GetState)
.def("set_green_time", &cc::TrafficLight::SetGreenTime, (arg("green_time")))
.def("get_green_time", &cc::TrafficLight::GetGreenTime)
.def("set_yellow_time", &cc::TrafficLight::SetYellowTime, (arg("yellow_time")))
.def("get_yellow_time", &cc::TrafficLight::GetYellowTime)
.def("set_red_time", &cc::TrafficLight::SetRedTime, (arg("red_time")))
.def("get_red_time", &cc::TrafficLight::GetRedTime)
.def("get_elapsed_time", &cc::TrafficLight::GetElapsedTime)
.def("freeze", &cc::TrafficLight::Freeze, (arg("freeze")))
.def("is_frozen", &cc::TrafficLight::IsFrozen)
.def("get_pole_index", &cc::TrafficLight::GetPoleIndex)
.def("get_group_traffic_lights", &GetGroupTrafficLights)
.add_property("state", &cc::TrafficLight::GetState, "@DocString(TrafficLight.state)")
.def("set_state", &cc::TrafficLight::SetState, (arg("state")), "@DocString(TrafficLight.set_state)")
.def("get_state", &cc::TrafficLight::GetState, "@DocString(TrafficLight.get_state)")
.def("set_green_time", &cc::TrafficLight::SetGreenTime, (arg("green_time")), "@DocString(TrafficLight.set_green_time)")
.def("get_green_time", &cc::TrafficLight::GetGreenTime, "@DocString(TrafficLight.get_green_time)")
.def("set_yellow_time", &cc::TrafficLight::SetYellowTime, (arg("yellow_time")), "@DocString(TrafficLight.set_yellow_time)")
.def("get_yellow_time", &cc::TrafficLight::GetYellowTime, "@DocString(TrafficLight.get_yellow_time)")
.def("set_red_time", &cc::TrafficLight::SetRedTime, (arg("red_time")), "@DocString(TrafficLight.set_red_time)")
.def("get_red_time", &cc::TrafficLight::GetRedTime, "@DocString(TrafficLight.get_red_time)")
.def("get_elapsed_time", &cc::TrafficLight::GetElapsedTime, "@DocString(TrafficLight.get_elapsed_time)")
.def("freeze", &cc::TrafficLight::Freeze, (arg("freeze")), "@DocString(TrafficLight.freeze)")
.def("is_frozen", &cc::TrafficLight::IsFrozen, "@DocString(TrafficLight.is_frozen)")
.def("get_pole_index", &cc::TrafficLight::GetPoleIndex, "@DocString(TrafficLight.get_pole_index)")
.def("get_group_traffic_lights", &GetGroupTrafficLights, "@DocString(TrafficLight.get_group_traffic_lights)")
.def(self_ns::str(self_ns::self))
;
}
Loading