diff --git a/CMakeLists.txt b/CMakeLists.txt
index 3fc57862b942..2161565d1a12 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -374,7 +374,7 @@ if(WITH_GUROBI)
endif()
endif()
-option(WITH_MOSEK "Build with support for MOSEK" OFF)
+option(WITH_MOSEK "Build with support for MOSEK™" OFF)
if(WITH_MOSEK)
list(APPEND BAZEL_CONFIGS --config=mosek)
diff --git a/doc/_pages/apt.md b/doc/_pages/apt.md
index 3f29e6184a4b..aa872d789055 100644
--- a/doc/_pages/apt.md
+++ b/doc/_pages/apt.md
@@ -20,8 +20,8 @@ Drake binary releases incorporate a pre-compiled version of
[Mathematical Program toolbox](https://drake.mit.edu/doxygen_cxx/group__solvers.html).
Thanks to Philip E. Gill and Elizabeth Wong for their kind support.
-Drake's apt packages do not support the Mosek nor Gurobi solvers. To use
-Mosek or Gurobi, you will need to [build Drake from source](/from_source.html).
+Drake's apt packages do not support the MOSEK™ nor Gurobi solvers. To use
+MOSEK™ or Gurobi, you will need to [build Drake from source](/from_source.html).
## Stable Releases
diff --git a/doc/_pages/bazel.md b/doc/_pages/bazel.md
index f69c4f330c5b..bb9a8c0e71e0 100644
--- a/doc/_pages/bazel.md
+++ b/doc/_pages/bazel.md
@@ -171,7 +171,7 @@ bazel build //tools/lint:buildifier
The Drake Bazel build currently supports the following proprietary solvers:
* Gurobi 9.0.2
-* MOSEK 9.2
+* MOSEK™ 9.2
* SNOPT 7.4
## Gurobi 9.0.2
@@ -203,17 +203,17 @@ See [https://docs.bazel.build/versions/master/user-manual.html#bazelrc](https://
## MOSEK
-The Drake Bazel build system downloads MOSEK 9.2.33 automatically. No manual
+The Drake Bazel build system downloads MOSEK™ 9.2.33 automatically. No manual
installation is required. Set the location of your license file as follows:
```export MOSEKLM_LICENSE_FILE=/path/to/mosek.lic```
-To confirm that your setup was successful, run the tests that require MOSEK:
+To confirm that your setup was successful, run the tests that require MOSEK™:
```bazel test --config mosek --test_tag_filters=mosek //...```
The default value of ``--test_tag_filters`` in Drake's ``bazel.rc`` excludes
-these tests. If you will be developing with MOSEK regularly, you may wish
+these tests. If you will be developing with MOSEK™ regularly, you may wish
to specify a more convenient ``--test_tag_filters`` in a local ``.bazelrc``.
See [https://docs.bazel.build/versions/master/user-manual.html#bazelrc](https://docs.bazel.build/versions/master/user-manual.html#bazelrc).
diff --git a/doc/_pages/docker.md b/doc/_pages/docker.md
index 84c4bbe2044b..a0cac55c3400 100644
--- a/doc/_pages/docker.md
+++ b/doc/_pages/docker.md
@@ -20,8 +20,8 @@ Drake binary releases incorporate a pre-compiled version of
[Mathematical Program toolbox](https://drake.mit.edu/doxygen_cxx/group__solvers.html).
Thanks to Philip E. Gill and Elizabeth Wong for their kind support.
-Drake's docker images do not support the Mosek nor Gurobi solvers. To use
-Mosek or Gurobi, you will need to [build Drake from source](/from_source.html).
+Drake's docker images do not support the MOSEK™ nor Gurobi solvers. To use
+MOSEK™ or Gurobi, you will need to [build Drake from source](/from_source.html).
## Stable Releases
diff --git a/doc/_pages/from_binary.md b/doc/_pages/from_binary.md
index f8c515f81810..ff7ffd828f2f 100644
--- a/doc/_pages/from_binary.md
+++ b/doc/_pages/from_binary.md
@@ -20,8 +20,8 @@ Drake binary releases incorporate a pre-compiled version of
[Mathematical Program toolbox](https://drake.mit.edu/doxygen_cxx/group__solvers.html).
Thanks to Philip E. Gill and Elizabeth Wong for their kind support.
-Drake's binary releases do not support the Mosek nor Gurobi solvers. To use
-Mosek or Gurobi, you will need to [build Drake from source](/from_source.html).
+Drake's binary releases do not support the MOSEK™ nor Gurobi solvers. To use
+MOSEK™ or Gurobi, you will need to [build Drake from source](/from_source.html).
## Stable Releases
diff --git a/doc/_pages/from_source.md b/doc/_pages/from_source.md
index 051e04ceeafa..2afaf347b774 100644
--- a/doc/_pages/from_source.md
+++ b/doc/_pages/from_source.md
@@ -105,12 +105,12 @@ make -j
Please note the additional CMake options which affect the Python bindings:
* ``-DWITH_GUROBI={ON, [OFF]}`` - Build with Gurobi enabled.
-* ``-DWITH_MOSEK={ON, [OFF]}`` - Build with MOSEK enabled.
+* ``-DWITH_MOSEK={ON, [OFF]}`` - Build with MOSEK™ enabled.
* ``-DWITH_SNOPT={ON, [OFF]}`` - Build with SNOPT enabled.
``{...}`` means a list of options, and the option surrounded by ``[...]`` is
the default option. An example of building ``pydrake`` with both Gurobi and
-MOSEK, without building tests:
+MOSEK™, without building tests:
```bash
cmake -DWITH_GUROBI=ON -DWITH_MOSEK=ON ../drake
diff --git a/doc/_pages/installation.md b/doc/_pages/installation.md
index 842caf7eb9b0..1ebab52c0fa0 100644
--- a/doc/_pages/installation.md
+++ b/doc/_pages/installation.md
@@ -83,8 +83,8 @@ All other packages support both C++ and/or Python.
Alternatively, you can skip the pre-compiled binaries and
[build Drake from source](/from_source.html).
-Drake's binary releases do not support the Mosek nor Gurobi solvers.
-To use Mosek or Gurobi, you must build Drake from source.
+Drake's binary releases do not support the MOSEK™ nor Gurobi solvers.
+To use MOSEK™ or Gurobi, you must build Drake from source.
We're considering adding macOS support for Homebrew, i.e., ``brew install
drake``. Please upvote or comment on
diff --git a/doc/_pages/pip.md b/doc/_pages/pip.md
index f073411c3191..b41787565129 100644
--- a/doc/_pages/pip.md
+++ b/doc/_pages/pip.md
@@ -21,8 +21,8 @@ Drake binary releases incorporate a pre-compiled version of
[Mathematical Program toolbox](https://drake.mit.edu/doxygen_cxx/group__solvers.html).
Thanks to Philip E. Gill and Elizabeth Wong for their kind support.
-Drake's pip packages do not support the Mosek nor Gurobi solvers. To use
-Mosek or Gurobi, you will need to [build Drake from source](/from_source.html).
+Drake's pip packages do not support the MOSEK™ nor Gurobi solvers. To use
+MOSEK™ or Gurobi, you will need to [build Drake from source](/from_source.html).
## Stable Releases
diff --git a/doc/_pages/tm.md b/doc/_pages/tm.md
new file mode 100644
index 000000000000..6f82eae59cf1
--- /dev/null
+++ b/doc/_pages/tm.md
@@ -0,0 +1,9 @@
+---
+title: Trademarks
+---
+
+All trademarks, logos and brand names are the property of their respective
+owners.
+
+MOSEK™ is a trademark of [MOSEK](https://www.mosek.com/) and is mentioned in
+Drake's documentation under a license from [MOSEK](https://www.mosek.com/).
diff --git a/doc/_release-notes/v0.13.0.md b/doc/_release-notes/v0.13.0.md
index f363a7fac626..6d7501b911eb 100644
--- a/doc/_release-notes/v0.13.0.md
+++ b/doc/_release-notes/v0.13.0.md
@@ -121,7 +121,7 @@ Newly bound
## Build system and dependencies
* Provide nightly binary docker images ([#10554][_#10554], [#12364][_#12364], [#12367][_#12367], [#12446][_#12446])
-* Fix missing pthread linkopts for MOSEK ([#12337][_#12337])
+* Fix missing pthread linkopts for MOSEK™ ([#12337][_#12337])
* Fix variable name in FindTinyXML2 ([#12339][_#12339])
* Fix ByteSizeLong for Protobuf 3.11.0 or above ([#12425][_#12425])
* Fix linters' find_all_sources --all commands ([#12369][_#12369], [#12385][_#12385], [#12424][_#12424])
diff --git a/doc/_release-notes/v0.25.0.md b/doc/_release-notes/v0.25.0.md
index c8fb7644e329..3b06fa133fd0 100644
--- a/doc/_release-notes/v0.25.0.md
+++ b/doc/_release-notes/v0.25.0.md
@@ -59,8 +59,8 @@ New features
Fixes
* Throw an error when getting dual solution for a QCP in Gurobi (`[#14285][_#14285])
-* Only retrieve Mosek dual solution when there are no integer variables ([#14338][_#14338]`)
-* Retrieve linear constraint dual from Mosek result ([#14348][_#14348])
+* Only retrieve MOSEK™ dual solution when there are no integer variables ([#14338][_#14338]`)
+* Retrieve linear constraint dual from MOSEK™ result ([#14348][_#14348])
* Ensure IPOPT uses MUMPS as its linear solver ([#14446][_#14446], [#14288][_#14288])
## Multibody Dynamics
diff --git a/doc/_release-notes/v0.26.0.md b/doc/_release-notes/v0.26.0.md
index 029571d722c4..a0eedf3ae2fa 100644
--- a/doc/_release-notes/v0.26.0.md
+++ b/doc/_release-notes/v0.26.0.md
@@ -39,7 +39,7 @@ Fixes
New features
-* Retrieve dual solution for conic constraint in Mosek ([#14383][_#14383])
+* Retrieve dual solution for conic constraint in MOSEK™ ([#14383][_#14383])
* Allow for incomplete symbolic derivatives ([#14514][_#14514])
Fixes
@@ -87,7 +87,7 @@ Newly bound
* Downgrade spdlog to release 5.1.0 ([#14427][_#14427])
* Upgrade fcl to latest commit ([#14497][_#14497])
* Upgrade ghc_filesystem to latest release 1.4.0 ([#14504][_#14504])
-* Upgrade mosek to latest release 9.2 ([#14484][_#14484])
+* Upgrade MOSEK™ to latest release 9.2 ([#14484][_#14484])
* Upgrade optitrack_driver to latest commit ([#14451][_#14451])
* Allow sphinx-build to be missing during bazel fetch ([#14528][_#14528])
* Add dependency on TRI common_robotics_utilities; for now this is only used by test code, but in a future release will be used by a forthcoming new drake/planning/... library ([#14437][_#14437], [#14530][_#14530])
diff --git a/doc/_release-notes/v0.39.0.md b/doc/_release-notes/v0.39.0.md
index 93f6bdbd8288..6fde11b5e908 100644
--- a/doc/_release-notes/v0.39.0.md
+++ b/doc/_release-notes/v0.39.0.md
@@ -59,7 +59,7 @@ New features
Fixes
* Improve performance while adding variables ([#16472][_#16472])
-* Mosek's debug printing includes the solution summary ([#16528][_#16528])
+* MOSEK™ debug printing includes the solution summary ([#16528][_#16528])
## Multibody Dynamics and Geometry
diff --git a/doc/defs.py b/doc/defs.py
index 1f8d72966edc..3b542275ad18 100644
--- a/doc/defs.py
+++ b/doc/defs.py
@@ -81,6 +81,35 @@ def check_call(args, *, cwd=None):
proc.check_returncode()
+def perl_cleanup_html_output(*, out_dir, extra_perl_statements=None):
+ """Runs a cleanup pass over all HTML output files, using a set of built-in
+ fixups. Calling code may pass its own extra statements, as well.
+ """
+ # Collect the list of all HTML output files.
+ html_files = []
+ for dirpath, _, filenames in os.walk(out_dir):
+ for filename in filenames:
+ if filename.endswith(".html"):
+ html_files.append(os.path.relpath(
+ os.path.join(dirpath, filename), out_dir))
+
+ # Figure out what to do.
+ default_perl_statements = [
+ # Add trademark hyperlink.
+ r's#™#™#g;',
+ ]
+ perl_statements = default_perl_statements + (extra_perl_statements or [])
+ for x in perl_statements:
+ assert x.endswith(';'), x
+
+ # Do it.
+ while html_files:
+ # Work in batches of 100, so we don't overflow the argv limit.
+ first, html_files = html_files[:100], html_files[100:]
+ check_call(["perl", "-pi", "-e", "".join(perl_statements)] + first,
+ cwd=out_dir)
+
+
def _call_build(*, build, out_dir):
"""Calls build() into out_dir, while also supplying a temp_dir."""
with tempfile.TemporaryDirectory(
diff --git a/doc/doxygen_cxx/build.py b/doc/doxygen_cxx/build.py
index c8f2c427aa66..f5111841e533 100644
--- a/doc/doxygen_cxx/build.py
+++ b/doc/doxygen_cxx/build.py
@@ -12,7 +12,13 @@
from bazel_tools.tools.python.runfiles import runfiles
-from drake.doc.defs import check_call, main, symlink_input, verbose
+from drake.doc.defs import (
+ check_call,
+ main,
+ perl_cleanup_html_output,
+ symlink_input,
+ verbose,
+)
def _symlink_headers(*, drake_workspace, temp_dir, modules):
@@ -246,15 +252,8 @@ def _build(*, out_dir, temp_dir, modules, quick):
]
_postprocess_doxygen_log(lines, check_for_errors)
- # Collect the list of all HTML output files.
- html_files = []
- for dirpath, _, filenames in os.walk(out_dir):
- for filename in filenames:
- if filename.endswith(".html"):
- html_files.append(relpath(join(dirpath, filename), out_dir))
-
# Fix the formatting of deprecation text (see drake#15619 for an example).
- perl_statements = [
+ extra_perl_statements = [
# Remove quotes around the removal date.
r's#(removed from Drake on or after) "(....-..-..)" *\.#\1 \2.#;',
# Remove all quotes within the explanation text, i.e., the initial and
@@ -267,11 +266,9 @@ def _build(*, out_dir, temp_dir, modules, quick):
#
"Use RotationMatrix::MakeFromOneVector()."
# noqa
r'while (s#(?<=_deprecated\d{6}")([^"]*)"(.*?
*
*
- * Mosek † |
+ * MOSEK™ †
* ♦ |
* ♦ |
* ♦ |
@@ -182,7 +182,7 @@
* |
*
*
- * Mosek † |
+ * MOSEK™ †
* ♦ |
* ♦ |
* ♦ |
diff --git a/solvers/mathematical_program_result.h b/solvers/mathematical_program_result.h
index 6c3cec3ea68e..30d635006acc 100644
--- a/solvers/mathematical_program_result.h
+++ b/solvers/mathematical_program_result.h
@@ -300,7 +300,7 @@ class MathematicalProgramResult final {
* 2. For nonlinear solvers like IPOPT, the dual solution for Lorentz cone
* constraint (with EvalType::kConvex) is the shadow price for
* z₀ - sqrt(z₁² + ... +zₙ²) ≥ 0, where z = Ax+b.
- * 3. For other convex conic solver such as SCS, Mosek, CSDP, etc, the dual
+ * 3. For other convex conic solver such as SCS, MOSEK™, CSDP, etc, the dual
* solution to the (rotated) Lorentz cone constraint doesn't have the
* "shadow price" interpretation, but should lie in the dual cone, and
* satisfy the KKT condition. For more information, refer to
@@ -310,7 +310,7 @@ class MathematicalProgramResult final {
* The interpretation for the dual variable to conic constraint x ∈ K can be
* different. Here K is a convex cone, including exponential cone, power
* cone, PSD cone, etc. When the problem is solved by a convex solver (like
- * SCS, Mosek, CSDP, etc), often it has a dual variable z ∈ K*, where K* is
+ * SCS, MOSEK™, CSDP, etc), often it has a dual variable z ∈ K*, where K* is
* the dual cone. Here the dual variable DOESN'T have the interpretation of
* "shadow price", but should satisfy the KKT condition, while the dual
* variable stays inside the dual cone.
diff --git a/solvers/mosek_solver.h b/solvers/mosek_solver.h
index 240302a8d853..d22c721969d5 100644
--- a/solvers/mosek_solver.h
+++ b/solvers/mosek_solver.h
@@ -12,15 +12,15 @@
namespace drake {
namespace solvers {
/**
- * The Mosek solver details after calling Solve() function. The user can call
+ * The MOSEK™ solver details after calling Solve() function. The user can call
* MathematicalProgramResult::get_solver_details() to obtain the
* details.
*/
struct MosekSolverDetails {
- /// The mosek optimization time. Please refer to MSK_DINF_OPTIMIZER_TIME in
+ /// The MOSEK™ optimization time. Please refer to MSK_DINF_OPTIMIZER_TIME in
/// https://docs.mosek.com/9.2/capi/constants.html?highlight=msk_dinf_optimizer_time
double optimizer_time{};
- /// The response code returned from mosek solver. Check
+ /// The response code returned from MOSEK™ solver. Check
/// https://docs.mosek.com/9.2/capi/response-codes.html for the meaning on the
/// response code.
int rescode{};
@@ -32,32 +32,32 @@ struct MosekSolverDetails {
};
/**
- * An implementation of SolverInterface for the commercially-licensed MOSEK
+ * An implementation of SolverInterface for the commercially-licensed MOSEK™
* solver (https://www.mosek.com/).
*
- * The default build of Drake is not configured to use MOSEK, so therefore
+ * The default build of Drake is not configured to use MOSEK™, so therefore
* SolverInterface::available() will return false. You must compile Drake
- * from source in order to link against MOSEK. For details, refer to the
+ * from source in order to link against MOSEK™. For details, refer to the
* documentation at https://drake.mit.edu/bazel.html#mosek.
*
* The MOSEKLM_LICENSE_FILE environment variable controls whether or not
* SolverInterface::enabled() returns true. Iff it is set to any non-empty
* value, then the solver is enabled; otherwise, the solver is not enabled.
*
- * @note Mosek only cares about the initial guess of integer variables. The
- * initial guess of continuous variables are not passed to MOSEK. If all the
- * integer variables are set to some integer values, then MOSEK will be forced
+ * @note MOSEK™ only cares about the initial guess of integer variables. The
+ * initial guess of continuous variables are not passed to MOSEK™. If all the
+ * integer variables are set to some integer values, then MOSEK™ will be forced
* to compute the remaining continuous variable values as the initial guess.
- * (Mosek might change the values of the integer/binary variables in the
+ * (MOSEK™ might change the values of the integer/binary variables in the
* subsequent iterations.) If the specified integer solution is infeasible or
- * incomplete, MOSEK will simply ignore it. For more details, check
+ * incomplete, MOSEK™ will simply ignore it. For more details, check
* https://docs.mosek.com/9.2/capi/tutorial-mio-shared.html?highlight=initial
*
- * Mosek supports many solver parameters. You can refer to the full list of
+ * MOSEK™ supports many solver parameters. You can refer to the full list of
* parameters in
* https://docs.mosek.com/9.2/capi/param-groups.html#doc-param-groups. On top of
* these parameters, we also provide the following additional parameters
- * 1. "writedata", set to a file name so that Mosek solver will write the
+ * 1. "writedata", set to a file name so that MOSEK™ solver will write the
* optimization model to this file. check
* https://docs.mosek.com/9.2/capi/solver-io.html#saving-a-problem-to-a-file
* for more details. The supported file extensions are listed in
@@ -82,16 +82,16 @@ class MosekSolver final : public SolverBase {
class License;
/**
- * This acquires a MOSEK license environment shared among all MosekSolver
+ * This acquires a MOSEK™ license environment shared among all MosekSolver
* instances; the environment will stay valid as long as at least one
* shared_ptr returned by this function is alive.
* Call this ONLY if you must use different MathematicalProgram
* instances at different instances in time, and repeatedly acquiring the
* license is costly (e.g., requires contacting a license server).
* @return A shared pointer to a license environment that will stay valid
- * as long as any shared_ptr returned by this function is alive. If MOSEK is
+ * as long as any shared_ptr returned by this function is alive. If MOSEK™ is
* not available in your build, this will return a null (empty) shared_ptr.
- * @throws std::exception if MOSEK is available but a license cannot be
+ * @throws std::exception if MOSEK™ is available but a license cannot be
* obtained.
*/
static std::shared_ptr AcquireLicense();
@@ -115,7 +115,7 @@ class MosekSolver final : public SolverBase {
const SolverOptions&, MathematicalProgramResult*) const final;
// Note that this is mutable to allow latching the allocation of mosek_env_
- // during the first call of Solve() (which avoids grabbing a Mosek license
+ // during the first call of Solve() (which avoids grabbing a MOSEK™ license
// before we know that we actually want one).
mutable std::shared_ptr license_;
};
diff --git a/solvers/solver_options.h b/solvers/solver_options.h
index 6ccef7aa9840..a1483f45c476 100644
--- a/solvers/solver_options.h
+++ b/solvers/solver_options.h
@@ -41,7 +41,7 @@ namespace solvers {
* Note that the SCS code on github master might be more up-to-date than the
* version used in Drake.
*
- * "MOSEK" -- Parameter name and values as specified in Mosek Reference
+ * "MOSEK™" -- Parameter name and values as specified in Mosek Reference
* https://docs.mosek.com/9.2/capi/parameters.html
*
* "OSQP" -- Parameter name and values as specified in OSQP Reference
diff --git a/tools/bazel.rc b/tools/bazel.rc
index 6355785383a9..010bfdd2a072 100644
--- a/tools/bazel.rc
+++ b/tools/bazel.rc
@@ -59,13 +59,13 @@ test --test_env=MPLBACKEND=Template
# -- If Gurobi is optional, set gurobi_required=False.
build:gurobi --define=WITH_GUROBI=ON
-### A configuration that enables MOSEK. ###
+### A configuration that enables MOSEK™. ###
# -- To use this config, the MOSEKLM_LICENSE_FILE environment variable must be
# -- set to the location of the MOSEK license file.
#
-# -- To run tests where MOSEK is used, ensure that you include
+# -- To run tests where MOSEK™ is used, ensure that you include
# -- "mosek_test_tags()" from //tools/skylark:test_tags.bzl.
-# -- If MOSEK is optional, set mosek_required=False.
+# -- If MOSEK™ is optional, set mosek_required=False.
build:mosek --define=WITH_MOSEK=ON
### A configuration that enables SNOPT. ###
diff --git a/tools/install/check_licenses.bzl b/tools/install/check_licenses.bzl
index b3a6b98446e6..67c741065afb 100644
--- a/tools/install/check_licenses.bzl
+++ b/tools/install/check_licenses.bzl
@@ -4,12 +4,12 @@ load("@drake//tools/install:install.bzl", "InstallInfo")
# List of exact file names of license files
LICENSE_LITERALS = [
- "BSD-LICENSE", # ccd
+ "BSD-LICENSE", # @ccd
"COPYING",
- "Copyright.txt", # vtk
- "EULA.pdf", # gurobi
+ "Copyright.txt", # @vtk
+ "EULA.pdf", # @gurobi
"LICENSE",
- "mosek-eula.pdf", # mosek
+ "mosek-eula.pdf", # @mosek
]
# List of file name prefixes of license files
diff --git a/tools/skylark/test_tags.bzl b/tools/skylark/test_tags.bzl
index 088872580ff9..5862d7ac8c2d 100644
--- a/tools/skylark/test_tags.bzl
+++ b/tools/skylark/test_tags.bzl
@@ -28,13 +28,13 @@ def gurobi_test_tags(gurobi_required = True):
return nominal_tags
def mosek_test_tags(mosek_required = True):
- """Returns the test tags necessary for properly running MOSEK tests.
+ """Returns the test tags necessary for properly running MOSEK™ tests.
By default, sets mosek_required=True, which will require that the supplied
tag filters include "mosek".
- MOSEK checks a license file outside the workspace, so tests that use MOSEK
- must have the tag "no-sandbox".
+ MOSEK™ checks a license file outside the workspace, so tests that use
+ MOSEK™ must have the tag "no-sandbox".
"""
nominal_tags = [
"no-sandbox",
diff --git a/tools/workspace/mosek/repository.bzl b/tools/workspace/mosek/repository.bzl
index eda055dc64d2..cf9a47aa2bb6 100644
--- a/tools/workspace/mosek/repository.bzl
+++ b/tools/workspace/mosek/repository.bzl
@@ -2,7 +2,7 @@
# vi: set ft=python :
"""
-Downloads and unpacks a MOSEK archive and makes its headers and
+Downloads and unpacks a MOSEK™ archive and makes its headers and
precompiled shared libraries available to be used as a C/C++
dependency.
@@ -108,9 +108,9 @@ def _impl(repository_ctx):
]
else:
files = [
- # N.B. We are using and installing MOSEK's copy of libcilkrts.so.5,
+ # N.B. We are using and installing the MOSEK™ copy of libcilkrts,
# even though Ubuntu installs the same shared library by default on
- # all systems already. For some reason, Mosek fails when used with
+ # all systems already. For some reason, MOSEK™ fails when used with
# Ubuntu's shared library. If Drake users have other third-party
# code that assumes use of Ubuntu's libcilkrts, there could be
# runtime conflicts; however, this risk seems low.
diff --git a/tutorials/linear_program.ipynb b/tutorials/linear_program.ipynb
index e5fcdabd3f9c..bbea4b9db312 100644
--- a/tutorials/linear_program.ipynb
+++ b/tutorials/linear_program.ipynb
@@ -25,7 +25,7 @@
"\n",
"$\\begin{aligned} \\min_x \\;c^Tx + d\\\\ \\text{subject to } Ax\\leq b \\end{aligned}$\n",
"\n",
- "A linear program can be solved by many open source or commercial solvers. Drake supports some solvers including SCS, Gurobi, Mosek, etc. Please see our [Doxygen page]( https://drake.mit.edu/doxygen_cxx/group__solvers.html) for a complete list of supported solvers. Note that some commercial solvers (such as Gurobi and Mosek) are not included in the pre-compiled Drake binaries, and therefore not on Binder/Colab. \n",
+ "A linear program can be solved by many open source or commercial solvers. Drake supports some solvers including SCS, Gurobi, MOSEK™, etc. Please see our [Doxygen page]( https://drake.mit.edu/doxygen_cxx/group__solvers.html) for a complete list of supported solvers. Note that some commercial solvers (such as Gurobi and MOSEK™) are not included in the pre-compiled Drake binaries, and therefore not on Binder/Colab. \n",
" \n",
"Drake's API supports multiple functions to add linear cost and constraints. We briefly go through some of the functions in this tutorial. For a complete list of functions, please check our [Doxygen](https://drake.mit.edu/doxygen_cxx/classdrake_1_1solvers_1_1_mathematical_program.html).\n",
"\n",
diff --git a/tutorials/quadratic_program.ipynb b/tutorials/quadratic_program.ipynb
index 4384763af553..c9d8a057a320 100644
--- a/tutorials/quadratic_program.ipynb
+++ b/tutorials/quadratic_program.ipynb
@@ -30,7 +30,7 @@
"\n",
"where `Q` is a positive semidefinite matrix.\n",
"\n",
- "A quadratic program can be solved by many different solvers. Drake supports some solvers including OSQP, SCS, Gurobi, Mosek, etc. Please see our [Doxygen page]( https://drake.mit.edu/doxygen_cxx/group__solvers.html) for a complete list of supported solvers. Note that some commercial solvers (such as Gurobi and Mosek) are not included in the pre-compiled Drake binaries, and therefore not on Binder/Colab. \n",
+ "A quadratic program can be solved by many different solvers. Drake supports some solvers including OSQP, SCS, Gurobi, MOSEK™, etc. Please see our [Doxygen page]( https://drake.mit.edu/doxygen_cxx/group__solvers.html) for a complete list of supported solvers. Note that some commercial solvers (such as Gurobi and MOSEK™) are not included in the pre-compiled Drake binaries, and therefore not on Binder/Colab. \n",
" \n",
"Drake's API supports multiple functions to add quadratic cost and linear constraints. We briefly go through some of the functions in this tutorial. For a complete list of functions, please check our [Doxygen](https://drake.mit.edu/doxygen_cxx/classdrake_1_1solvers_1_1_mathematical_program.html).\n",
"\n",
@@ -212,7 +212,7 @@
"metadata": {},
"source": [
"## Convexity of the cost\n",
- "Drake checks the convexity of every added quadratic cost, by checking whether the Hessian of each quadratic cost is positive semidefinite or not. Currently the user can solve a QP with a convex solver (Gurobi/Mosek/OSQP/CLP/SCS etc) only if every quadratic cost is convex.\n",
+ "Drake checks the convexity of every added quadratic cost, by checking whether the Hessian of each quadratic cost is positive semidefinite or not. Currently the user can solve a QP with a convex solver (Gurobi/MOSEK™/OSQP/CLP/SCS etc) only if every quadratic cost is convex.\n",
"\n",
"It takes some computation to check if a quadratic cost is convex. If your application requires solving the QP as fast as possible (for example, solving a QP within the robot control loop), then it makes sense to bypass this convexity check. To do so, if you know the convexity of your quadratic cost, you can set the `is_convex` flag in `AddQuadraticCost` function; Drake won't compute whether the cost is convex or not when the `is_convex` flag is set. In the following example we show how to set this `is_convex` flag."
]