Skip to content

Commit d4f321a

Browse files
committed
ci: get git to work on ci
1 parent fe05cec commit d4f321a

File tree

6 files changed

+32
-48
lines changed

6 files changed

+32
-48
lines changed

.bazelrc

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,3 +61,5 @@ build:omp --linkopt=-fopenmp
6161

6262
# use python3 by default
6363
build --python_path=python3
64+
65+
build --local_cpu_resources=3

.cirrus.yml

Lines changed: 11 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -5,19 +5,10 @@ build_jammy_task:
55
cpu: 8
66
memory: 24
77
test_script:
8-
- export CC=clang-15
9-
- export CXX=clang++-15
10-
- bazel build
11-
--define=WITH_SNOPT=OFF
12-
--local_ram_resources=24000
13-
--local_cpu_resources=8
14-
--jobs=8
15-
//...
16-
- bazel test
17-
--define=WITH_SNOPT=OFF
18-
--local_ram_resources=24000
19-
--local_cpu_resources=8
20-
//...
8+
- export CC=clang-15
9+
- export CXX=clang++-15
10+
- bazel build --define=WITH_GUROBI=OFF --define=WITH_SNOPT=OFF --local_ram_resources=24000 --local_cpu_resources=8 --jobs=8 //...
11+
- bazel test --define=WITH_SNOPT=OFF --local_ram_resources=24000 --local_cpu_resources=8 //...
2112
drake_master_build_task:
2213
timeout_in: 120m
2314
container:
@@ -28,20 +19,10 @@ drake_master_build_task:
2819
env:
2920
DAIRLIB_WITH_ROS: ON
3021
test_script:
31-
- git clone https://github.com/RobotLocomotion/drake.git ../drake
32-
- export DAIRLIB_LOCAL_DRAKE_PATH=$PWD/../drake
33-
- cd tools/workspace/ros
34-
- ./compile_ros_workspace.sh
35-
- cd ../../../
36-
- bazel build
37-
--define=WITH_SNOPT=OFF
38-
--local_ram_resources=24000
39-
--local_cpu_resources=8
40-
--jobs=8
41-
//...
42-
- bazel test
43-
--define=WITH_SNOPT=OFF
44-
--local_ram_resources=24000
45-
--local_cpu_resources=8
46-
--jobs=8
47-
//...
22+
- git clone https://github.com/RobotLocomotion/drake.git ../drake
23+
- export DAIRLIB_LOCAL_DRAKE_PATH=$PWD/../drake
24+
- cd tools/workspace/ros
25+
- ./compile_ros_workspace.sh
26+
- cd ../../../
27+
- bazel build --define=WITH_GUROBI=OFF --define=WITH_SNOPT=OFF --local_ram_resources=24000 --local_cpu_resources=8 --jobs=8 //...
28+
- bazel test --define=WITH_SNOPT=OFF --local_ram_resources=24000 --local_cpu_resources=8 --jobs=8 //...

bindings/pydairlib/systems/robot_lcm_systems_py.cc

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,21 +29,20 @@ PYBIND11_MODULE(robot_lcm_systems, m) {
2929
m, "RobotOutputSender")
3030
.def(py::init<const MultibodyPlant<double>&, bool>())
3131
.def("get_input_port_state", &RobotOutputSender::get_input_port_state,
32-
py_rvp::reference_internal)
32+
py_rvp::reference_internal)
3333
.def("get_input_port_effort", &RobotOutputSender::get_input_port_effort,
34-
py_rvp::reference_internal)
34+
py_rvp::reference_internal)
3535
.def("get_input_port_imu", &RobotOutputSender::get_input_port_imu,
36-
py_rvp::reference_internal);
36+
py_rvp::reference_internal);
3737
py::class_<systems::RobotCommandSender, drake::systems::LeafSystem<double>>(
3838
m, "RobotCommandSender")
3939
.def(py::init<const MultibodyPlant<double>&>());
4040
m.def("AddActuationRecieverAndStateSenderLcm",
4141
&dairlib::systems::AddActuationRecieverAndStateSenderLcm,
4242
py::arg("builder"), py::arg("plant"), py::arg("lcm"),
4343
py::arg("actuator_channel"), py::arg("state_channel"),
44-
py::arg("publish_rate"), py::arg("publish_efforts"),
45-
py::arg("actuator_delay"));
46-
44+
py::arg("publish_rate"), py::arg("model_instance_index"),
45+
py::arg("publish_efforts"), py::arg("actuator_delay"));
4746
}
4847

4948
} // namespace pydairlib

install/focal/ros/Dockerfile

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ WORKDIR /dairlib
33
ENV DAIRLIB_DOCKER_VERSION_26=26
44
ENV ROS_PYTHON_VERSION=3
55
COPY . .
6-
RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python
6+
RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python git
77
RUN apt-get install -y python3-rosinstall-generator python3-catkin-tools python3-vcstool python3-osrf-pycommon python3-vcstool python3-empy clang-12 clang-format-12
88
RUN set -eux \
99
&& apt-get install --no-install-recommends locales \

install/jammy/Dockerfile

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ FROM ubuntu:jammy
22
WORKDIR ./dairlib
33
ENV DAIRLIB_DOCKER_VERSION_25=25
44
COPY . .
5-
RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip clang-15 clang-format-15 ca-certificates gnupg
5+
RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip clang-15 clang-format-15 ca-certificates gnupg git
66
RUN set -eux \
77
&& apt-get install --no-install-recommends locales \
88
&& locale-gen en_US.UTF-8

systems/framework/geared_motor.cc

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,14 @@
55
namespace dairlib {
66
namespace systems {
77

8+
using drake::BasicVector;
89
using drake::multibody::JointActuator;
910
using drake::multibody::MultibodyPlant;
1011
using drake::systems::kUseDefaultName;
1112

12-
GearedMotor::GearedMotor(const MultibodyPlant<double>& plant,
13-
const std::unordered_map<std::string, double>& max_motor_speeds)
13+
GearedMotor::GearedMotor(
14+
const MultibodyPlant<double>& plant,
15+
const std::unordered_map<std::string, double>& max_motor_speeds)
1416
: n_q(plant.num_positions()),
1517
n_v(plant.num_velocities()),
1618
n_u(plant.num_actuators()),
@@ -19,11 +21,12 @@ GearedMotor::GearedMotor(const MultibodyPlant<double>& plant,
1921
const JointActuator<double>& joint_actuator =
2022
plant.get_joint_actuator(drake::multibody::JointActuatorIndex(i));
2123
actuator_gear_ratios.push_back(joint_actuator.default_gear_ratio());
22-
actuator_ranges.push_back(joint_actuator.effort_limit() / joint_actuator.default_gear_ratio());
24+
actuator_ranges.push_back(joint_actuator.effort_limit() /
25+
joint_actuator.default_gear_ratio());
2326
actuator_max_speeds.push_back(max_motor_speeds.at(joint_actuator.name()));
2427
}
25-
systems::BasicVector<double> input(plant.num_actuators());
26-
systems::BasicVector<double> output(plant.num_actuators());
28+
BasicVector<double> input(plant.num_actuators());
29+
BasicVector<double> output(plant.num_actuators());
2730

2831
command_input_port_ =
2932
this->DeclareVectorInputPort("u_cmd", input).get_index();
@@ -36,11 +39,10 @@ GearedMotor::GearedMotor(const MultibodyPlant<double>& plant,
3639

3740
void GearedMotor::CalcTorqueOutput(
3841
const drake::systems::Context<double>& context,
39-
systems::BasicVector<double>* output) const {
40-
const systems::BasicVector<double>& u =
41-
*this->template EvalVectorInput<BasicVector>(context,
42-
command_input_port_);
43-
const systems::BasicVector<double>& x =
42+
BasicVector<double>* output) const {
43+
const BasicVector<double>& u = *this->template EvalVectorInput<BasicVector>(
44+
context, command_input_port_);
45+
const BasicVector<double>& x =
4446
*this->template EvalVectorInput<BasicVector>(context, state_input_port_);
4547
Eigen::VectorXd actuator_velocities = B_.transpose() * x.value().tail(n_v);
4648
Eigen::VectorXd tau = Eigen::VectorXd::Zero(n_u);

0 commit comments

Comments
 (0)